Merge branch 'master' of github.com:markqvist/RNode_Firmware

This commit is contained in:
Mark Qvist 2024-01-21 11:55:02 +01:00
commit b88e84ab22
15 changed files with 1956 additions and 408 deletions

View File

@ -14,6 +14,7 @@
// along with this program. If not, see <https://www.gnu.org/licenses/>.
#include "ROM.h"
#include "Modem.h"
#ifndef CONFIG_H
#define CONFIG_H
@ -23,10 +24,12 @@
#define PLATFORM_AVR 0x90
#define PLATFORM_ESP32 0x80
#define PLATFORM_NRF52 0x70
#define MCU_1284P 0x91
#define MCU_2560 0x92
#define MCU_ESP32 0x81
#define MCU_NRF52 0x71
#define BOARD_RNODE 0x31
#define BOARD_HMBRW 0x32
@ -39,6 +42,8 @@
#define BOARD_HELTEC32_V2 0x38
#define BOARD_RNODE_NG_20 0x40
#define BOARD_RNODE_NG_21 0x41
#define BOARD_GENERIC_NRF52 0x50
#define BOARD_RAK4630 0x51
#define MODE_HOST 0x11
#define MODE_TNC 0x12
@ -61,7 +66,7 @@
#define M_FRQ_S 27388122
#define M_FRQ_R 27388061
bool console_active = false;
bool sx1276_installed = false;
bool modem_installed = false;
#if defined(__AVR_ATmega1284P__)
#define PLATFORM PLATFORM_AVR
@ -72,6 +77,9 @@
#elif defined(ESP32)
#define PLATFORM PLATFORM_ESP32
#define MCU_VARIANT MCU_ESP32
#elif defined(NRF52840_XXAA)
#define PLATFORM PLATFORM_NRF52
#define MCU_VARIANT MCU_NRF52
#else
#error "The firmware cannot be compiled for the selected MCU variant"
#endif
@ -90,6 +98,7 @@
#define HAS_TCXO false
#define HAS_PMU false
#define HAS_NP false
#define HAS_EEPROM false
#if defined(ENABLE_TCXO)
#define HAS_TCXO true
@ -104,6 +113,8 @@
#define BOARD_MODEL BOARD_RNODE
#define HAS_EEPROM true
#define CONFIG_UART_BUFFER_SIZE 6144
#define CONFIG_QUEUE_SIZE 6144
#define CONFIG_QUEUE_MAX_LENGTH 200
@ -120,6 +131,8 @@
#define BOARD_MODEL BOARD_HMBRW
#define HAS_EEPROM true
#define CONFIG_UART_BUFFER_SIZE 768
#define CONFIG_QUEUE_SIZE 5120
#define CONFIG_QUEUE_MAX_LENGTH 24
@ -135,6 +148,16 @@
// firmware, you can manually define model here.
//
// #define BOARD_MODEL BOARD_GENERIC_ESP32
#define CONFIG_UART_BUFFER_SIZE 6144
#define CONFIG_QUEUE_SIZE 6144
#define CONFIG_QUEUE_MAX_LENGTH 200
#define EEPROM_SIZE 1024
#define EEPROM_OFFSET EEPROM_SIZE-EEPROM_RESERVED
#define GPS_BAUD_RATE 9600
#define PIN_GPS_TX 12
#define PIN_GPS_RX 34
#if BOARD_MODEL == BOARD_GENERIC_ESP32
const int pin_cs = 4;
@ -144,6 +167,7 @@
const int pin_led_tx = 32;
#define HAS_BLUETOOTH true
#define HAS_CONSOLE true
#define HAS_EEPROM true
#elif BOARD_MODEL == BOARD_TBEAM
const int pin_cs = 18;
const int pin_reset = 23;
@ -156,6 +180,7 @@
#define HAS_BLUETOOTH true
#define HAS_CONSOLE true
#define HAS_SD false
#define HAS_EEPROM true
#elif BOARD_MODEL == BOARD_HUZZAH32
const int pin_cs = 4;
const int pin_reset = 36;
@ -268,24 +293,44 @@
const int pin_led_tx = 25;
#endif
#endif
#else
#error An unsupported board was selected. Cannot compile RNode firmware.
#endif
#endif
#elif PLATFORM == PLATFORM_NRF52
#if BOARD_MODEL == BOARD_RAK4630
#define HAS_EEPROM false
#define HAS_DISPLAY false // set for debugging
#define HAS_BLUETOOTH false
#define HAS_CONSOLE false
#define HAS_PMU false
#define HAS_NP false
#define HAS_SD false
#define HAS_TCXO true
#define HAS_RXEN_BUSY true
#define MODEM SX1262
bool mw_radio_online = false;
#define CONFIG_UART_BUFFER_SIZE 6144
#define CONFIG_QUEUE_SIZE 6144
#define CONFIG_QUEUE_MAX_LENGTH 200
#define EEPROM_SIZE 4096
#define EEPROM_OFFSET EEPROM_SIZE+0xED000-EEPROM_RESERVED
#define CONFIG_UART_BUFFER_SIZE 6144
#define CONFIG_QUEUE_SIZE 6144
#define CONFIG_QUEUE_MAX_LENGTH 200
#define EEPROM_SIZE 1024
#define EEPROM_OFFSET EEPROM_SIZE-EEPROM_RESERVED
#define GPS_BAUD_RATE 9600
#define PIN_GPS_TX 12
#define PIN_GPS_RX 34
// following pins are for the sx1262
const int pin_rxen = 37;
const int pin_reset = 38;
const int pin_cs = 42;
const int pin_sclk = 43;
const int pin_mosi = 44;
const int pin_miso = 45;
const int pin_busy = 46;
const int pin_dio = 47;
const int pin_led_rx = LED_BLUE;
const int pin_led_tx = LED_GREEN;
#endif
#else
#error An unsupported board was selected. Cannot compile RNode firmware.
#endif
bool mw_radio_online = false;
#if BOARD_MODEL == BOARD_TBEAM
#define I2C_SDA 21
#define I2C_SCL 22
@ -294,6 +339,15 @@
#define eeprom_addr(a) (a+EEPROM_OFFSET)
#ifndef HAS_RXEN_BUSY
const int pin_rxen = -1;
const int pin_busy = -1;
#endif
#if MODEM == SX1262
SPIClass spiModem(NRF_SPIM2, pin_miso, pin_sclk, pin_mosi);
#endif
// MCU independent configuration parameters
const long serial_baudrate = 115200;
@ -361,7 +415,7 @@
uint32_t stat_tx = 0;
#define STATUS_INTERVAL_MS 3
#if MCU_VARIANT == MCU_ESP32
#if MCU_VARIANT == MCU_ESP32 || MCU_VARIANT == MCU_NRF52
#define DCD_SAMPLES 2500
#define UTIL_UPDATE_INTERVAL_MS 1000
#define UTIL_UPDATE_INTERVAL (UTIL_UPDATE_INTERVAL_MS/STATUS_INTERVAL_MS)

View File

@ -14,13 +14,18 @@
// along with this program. If not, see <https://www.gnu.org/licenses/>.
#include <Ed25519.h>
#if MCU_VARIANT == MCU_ESP32
#include "mbedtls/md.h"
#include "esp_ota_ops.h"
#include "esp_flash_partitions.h"
#include "esp_partition.h"
#endif
// Forward declaration from Utilities.h
void eeprom_update(int mapped_addr, uint8_t byte);
uint8_t eeprom_read(uint32_t addr);
void hard_reset(void);
const uint8_t dev_keys [] PROGMEM = {
@ -86,13 +91,21 @@ void device_save_signature() {
void device_load_signature() {
for (uint8_t i = 0; i < DEV_SIG_LEN; i++) {
dev_sig[i] = EEPROM.read(dev_sig_addr(i));
#if HAS_EEPROM
dev_sig[i] = EEPROM.read(dev_sig_addr(i));
#elif MCU_VARIANT == MCU_NRF52
dev_sig[i] = eeprom_read(dev_sig_addr(i));
#endif
}
}
void device_load_firmware_hash() {
for (uint8_t i = 0; i < DEV_HASH_LEN; i++) {
dev_firmware_hash_target[i] = EEPROM.read(dev_fwhash_addr(i));
#if HAS_EEPROM
dev_firmware_hash_target[i] = EEPROM.read(dev_fwhash_addr(i));
#elif MCU_VARIANT == MCU_NRF52
dev_firmware_hash_target[i] = eeprom_read(dev_fwhash_addr(i));
#endif
}
}
@ -103,6 +116,7 @@ void device_save_firmware_hash() {
if (!fw_signature_validated) hard_reset();
}
#if MCU_VARIANT == MCU_ESP32
void device_validate_partitions() {
device_load_firmware_hash();
esp_partition_t partition;
@ -122,11 +136,13 @@ void device_validate_partitions() {
}
}
}
#endif
bool device_firmware_ok() {
return fw_signature_validated;
}
#if MCU_VARIANT == MCU_ESP32
bool device_init() {
if (bt_ready) {
for (uint8_t i=0; i<EEPROM_SIG_LEN; i++){dev_eeprom_signature[i]=EEPROM.read(eeprom_addr(ADDR_SIGNATURE+i));}
@ -148,3 +164,4 @@ bool device_init() {
return false;
}
}
#endif

View File

@ -452,7 +452,7 @@ void draw_disp_area() {
if (!device_firmware_ok()) {
disp_area.drawBitmap(0, 37, bm_fw_corrupt, disp_area.width(), 27, SSD1306_WHITE, SSD1306_BLACK);
} else {
if (!sx1276_installed) {
if (!modem_installed) {
disp_area.drawBitmap(0, 37, bm_no_radio, disp_area.width(), 27, SSD1306_WHITE, SSD1306_BLACK);
} else {
disp_area.drawBitmap(0, 37, bm_hwfail, disp_area.width(), 27, SSD1306_WHITE, SSD1306_BLACK);

1387
LoRa.cpp

File diff suppressed because it is too large Load Diff

40
LoRa.h
View File

@ -9,10 +9,13 @@
#include <Arduino.h>
#include <SPI.h>
#include "Modem.h"
#define LORA_DEFAULT_SS_PIN 10
#define LORA_DEFAULT_RESET_PIN 9
#define LORA_DEFAULT_DIO0_PIN 2
#define LORA_DEFAULT_RXEN_PIN -1
#define LORA_DEFAULT_BUSY_PIN -1
#define PA_OUTPUT_RFO_PIN 0
#define PA_OUTPUT_PA_BOOST_PIN 1
@ -71,13 +74,26 @@ public:
void enableTCXO();
void disableTCXO();
#if MODEM == SX1262
void enableAntenna();
void disableAntenna();
void loraMode();
void waitOnBusy();
void executeOpcode(uint8_t opcode, uint8_t *buffer, uint8_t size);
void executeOpcodeRead(uint8_t opcode, uint8_t *buffer, uint8_t size);
void writeBuffer(const uint8_t* buffer, size_t size);
void readBuffer(uint8_t* buffer, size_t size);
void setModulationParams(uint8_t sf, uint8_t bw, uint8_t cr, int ldro);
void setPacketParams(long preamble, uint8_t headermode, uint8_t length, uint8_t crc);
#endif
// deprecated
void crc() { enableCrc(); }
void noCrc() { disableCrc(); }
byte random();
void setPins(int ss = LORA_DEFAULT_SS_PIN, int reset = LORA_DEFAULT_RESET_PIN, int dio0 = LORA_DEFAULT_DIO0_PIN);
void setPins(int ss = LORA_DEFAULT_SS_PIN, int reset = LORA_DEFAULT_RESET_PIN, int dio0 = LORA_DEFAULT_DIO0_PIN, int rxen = LORA_DEFAULT_RXEN_PIN, int busy = LORA_DEFAULT_BUSY_PIN);
void setSPIFrequency(uint32_t frequency);
void dumpRegisters(Stream& out);
@ -88,9 +104,15 @@ private:
void handleDio0Rise();
uint8_t readRegister(uint8_t address);
void writeRegister(uint8_t address, uint8_t value);
uint8_t singleTransfer(uint8_t address, uint8_t value);
#if MODEM == SX1276 || MODEM == SX1278
uint8_t readRegister(uint8_t address);
void writeRegister(uint8_t address, uint8_t value);
uint8_t singleTransfer(uint8_t address, uint8_t value);
#elif MODEM == SX1262
uint8_t readRegister(uint16_t address);
void writeRegister(uint16_t address, uint8_t value);
uint8_t singleTransfer(uint8_t opcode, uint16_t address, uint8_t value);
#endif
static void onDio0Rise();
@ -102,9 +124,19 @@ private:
int _ss;
int _reset;
int _dio0;
int _rxen;
int _busy;
long _frequency;
int _txp;
uint8_t _sf;
uint8_t _bw;
uint8_t _cr;
uint8_t _ldro;
int _packetIndex;
int _preambleLength;
int _implicitHeaderMode;
int _payloadLength;
int _crcMode;
void (*_onReceive)(int);
};

View File

@ -37,6 +37,10 @@ prep-samd:
arduino-cli core update-index --config-file arduino-cli.yaml
arduino-cli core install adafruit:samd
prep-nrf:
arduino-cli core update-index --config-file arduino-cli.yaml
arduino-cli core install rakwireless:nrf52
console-site:
make -C Console clean site
@ -92,8 +96,10 @@ firmware-featheresp32:
arduino-cli compile --fqbn esp32:esp32:featheresp32 -e --build-property "build.partitions=no_ota" --build-property "upload.maximum_size=2097152" --build-property "compiler.cpp.extra_flags=\"-DBOARD_MODEL=0x34\""
firmware-genericesp32:
arduino-cli compile --fqbn esp32:esp32:esp32 -e --build-property "build.partitions=no_ota" --build-property "upload.maximum_size=2097152" --build-property "compiler.cpp.extra_flags=\"-DBOARD_MODEL=0x35\""
arduino-cli compile --fqbn esp32:esp32:esp32 -e --build-property "build.partitions=no_ota" --build-property "upload.maximum_size=2097152" --build-property "compiler.cpp.extra_flags=\"-DBOARD_MODEL=0x35\" \"-DMODEM=0x01\""
firmware-rak4630:
arduino-cli compile --fqbn rakwireless:nrf52:WisCoreRAK4631Board -e --build-property "build.partitions=no_ota" --build-property "upload.maximum_size=2097152" --build-property "compiler.cpp.extra_flags=\"-DBOARD_MODEL=0x51\" \"-DMODEM=0x03\""
upload:
arduino-cli upload -p /dev/ttyUSB0 --fqbn unsignedio:avr:rnode
@ -157,6 +163,10 @@ upload-featheresp32:
@sleep 3
python ./Release/esptool/esptool.py --chip esp32 --port /dev/ttyUSB0 --baud 921600 --before default_reset --after hard_reset write_flash -z --flash_mode dio --flash_freq 80m --flash_size 4MB 0x210000 ./Release/console_image.bin
upload-rak4630:
arduino-cli upload -p /dev/ttyACM0 --fqbn rakwireless:nrf52:WisCoreRAK4631Board
release: release-all

3
Modem.h Normal file
View File

@ -0,0 +1,3 @@
#define SX1276 0x01
#define SX1278 0x02
#define SX1262 0x03

View File

@ -43,7 +43,7 @@ volatile bool serial_buffering = false;
char sbuf[128];
#if MCU_VARIANT == MCU_ESP32
#if MCU_VARIANT == MCU_ESP32 || MCU_VARIANT == MCU_NRF52
bool packet_ready = false;
#endif
@ -91,15 +91,15 @@ void setup() {
// Set chip select, reset and interrupt
// pins for the LoRa module
LoRa.setPins(pin_cs, pin_reset, pin_dio);
LoRa.setPins(pin_cs, pin_reset, pin_dio, pin_rxen, pin_busy);
#if MCU_VARIANT == MCU_ESP32
#if MCU_VARIANT == MCU_ESP32 || MCU_VARIANT == MCU_NRF52
init_channel_stats();
// Check installed transceiver chip and
// probe boot parameters.
if (LoRa.preInit()) {
sx1276_installed = true;
modem_installed = true;
uint32_t lfr = LoRa.getFrequency();
if (lfr == 0) {
// Normal boot
@ -115,12 +115,12 @@ void setup() {
}
LoRa.setFrequency(M_FRQ_S);
} else {
sx1276_installed = false;
modem_installed = false;
}
#else
// Older variants only came with SX1276/78 chips,
// so assume that to be the case for now.
sx1276_installed = true;
modem_installed = true;
#endif
#if HAS_DISPLAY
@ -178,7 +178,7 @@ inline void kiss_write_packet() {
}
serial_write(FEND);
read_len = 0;
#if MCU_VARIANT == MCU_ESP32
#if MCU_VARIANT == MCU_ESP32 || MCU_VARIANT == MCU_NRF52
packet_ready = false;
#endif
}
@ -207,7 +207,7 @@ void ISR_VECT receive_callback(int packet_size) {
read_len = 0;
seq = sequence;
#if MCU_VARIANT != MCU_ESP32
#if MCU_VARIANT != MCU_ESP32 && MCU_VARIANT != MCU_NRF52
last_rssi = LoRa.packetRssi();
last_snr_raw = LoRa.packetSnrRaw();
#endif
@ -219,12 +219,14 @@ void ISR_VECT receive_callback(int packet_size) {
// packet, so we add it to the buffer
// and set the ready flag.
#if MCU_VARIANT != MCU_ESP32
#if MCU_VARIANT != MCU_ESP32 && MCU_VARIANT != MCU_NRF52
last_rssi = (last_rssi+LoRa.packetRssi())/2;
last_snr_raw = (last_snr_raw+LoRa.packetSnrRaw())/2;
#endif
getPacketData(packet_size);
seq = SEQ_UNSET;
ready = true;
@ -236,7 +238,7 @@ void ISR_VECT receive_callback(int packet_size) {
read_len = 0;
seq = sequence;
#if MCU_VARIANT != MCU_ESP32
#if MCU_VARIANT != MCU_ESP32 && MCU_VARIANT != MCU_NRF52
last_rssi = LoRa.packetRssi();
last_snr_raw = LoRa.packetSnrRaw();
#endif
@ -255,7 +257,7 @@ void ISR_VECT receive_callback(int packet_size) {
seq = SEQ_UNSET;
}
#if MCU_VARIANT != MCU_ESP32
#if MCU_VARIANT != MCU_ESP32 && MCU_VARIANT != MCU_NRF52
last_rssi = LoRa.packetRssi();
last_snr_raw = LoRa.packetSnrRaw();
#endif
@ -265,7 +267,7 @@ void ISR_VECT receive_callback(int packet_size) {
}
if (ready) {
#if MCU_VARIANT != MCU_ESP32
#if MCU_VARIANT != MCU_ESP32 && MCU_VARIANT != MCU_NRF52
// We first signal the RSSI of the
// recieved packet to the host.
kiss_indicate_stat_rssi();
@ -282,7 +284,7 @@ void ISR_VECT receive_callback(int packet_size) {
// output directly to the host
read_len = 0;
#if MCU_VARIANT != MCU_ESP32
#if MCU_VARIANT != MCU_ESP32 && MCU_VARIANT != MCU_NRF52
last_rssi = LoRa.packetRssi();
last_snr_raw = LoRa.packetSnrRaw();
getPacketData(packet_size);
@ -380,7 +382,7 @@ void flushQueue(void) {
led_tx_on();
uint16_t processed = 0;
#if MCU_VARIANT == MCU_ESP32
#if MCU_VARIANT == MCU_ESP32 || MCU_VARIANT == MCU_NRF52
while (!fifo16_isempty(&packet_starts)) {
#else
while (!fifo16_isempty_locked(&packet_starts)) {
@ -407,7 +409,7 @@ void flushQueue(void) {
queue_height = 0;
queued_bytes = 0;
#if MCU_VARIANT == MCU_ESP32
#if MCU_VARIANT == MCU_ESP32 || MCU_VARIANT == MCU_NRF52
update_airtime();
#endif
queue_flushing = false;
@ -415,7 +417,7 @@ void flushQueue(void) {
#define PHY_HEADER_LORA_SYMBOLS 8
void add_airtime(uint16_t written) {
#if MCU_VARIANT == MCU_ESP32
#if MCU_VARIANT == MCU_ESP32 || MCU_VARIANT == MCU_NRF52
float packet_cost_ms = 0.0;
float payload_cost_ms = ((float)written * lora_us_per_byte)/1000.0;
packet_cost_ms += payload_cost_ms;
@ -429,7 +431,7 @@ void add_airtime(uint16_t written) {
}
void update_airtime() {
#if MCU_VARIANT == MCU_ESP32
#if MCU_VARIANT == MCU_ESP32 || MCU_VARIANT == MCU_NRF52
uint16_t cb = current_airtime_bin();
uint16_t pb = cb-1; if (cb-1 < 0) { pb = AIRTIME_BINS-1; }
uint16_t nb = cb+1; if (nb == AIRTIME_BINS) { nb = 0; }
@ -448,7 +450,7 @@ void update_airtime() {
}
longterm_channel_util = (float)longterm_channel_util_sum/(float)AIRTIME_BINS;
#if MCU_VARIANT == MCU_ESP32
#if MCU_VARIANT == MCU_ESP32 || MCU_VARIANT == MCU_NRF52
update_csma_p();
#endif
kiss_indicate_channel_stats();
@ -818,13 +820,13 @@ void serialCallback(uint8_t sbyte) {
kiss_indicate_fb();
}
} else if (command == CMD_DEV_HASH) {
#if MCU_VARIANT == MCU_ESP32
#if MCU_VARIANT == MCU_ESP32 || MCU_VARIANT == MCU_NRF52
if (sbyte != 0x00) {
kiss_indicate_device_hash();
}
#endif
} else if (command == CMD_DEV_SIG) {
#if MCU_VARIANT == MCU_ESP32
#if MCU_VARIANT == MCU_ESP32 || MCU_VARIANT == MCU_NRF52
if (sbyte == FESC) {
ESCAPE = true;
} else {
@ -848,7 +850,7 @@ void serialCallback(uint8_t sbyte) {
firmware_update_mode = false;
}
} else if (command == CMD_HASHES) {
#if MCU_VARIANT == MCU_ESP32
#if MCU_VARIANT == MCU_ESP32 || MCU_VARIANT == MCU_NRF52
if (sbyte == 0x01) {
kiss_indicate_target_fw_hash();
} else if (sbyte == 0x02) {
@ -860,7 +862,7 @@ void serialCallback(uint8_t sbyte) {
}
#endif
} else if (command == CMD_FW_HASH) {
#if MCU_VARIANT == MCU_ESP32
#if MCU_VARIANT == MCU_ESP32 || MCU_VARIANT == MCU_NRF52
if (sbyte == FESC) {
ESCAPE = true;
} else {
@ -930,6 +932,8 @@ void serialCallback(uint8_t sbyte) {
void updateModemStatus() {
#if MCU_VARIANT == MCU_ESP32
portENTER_CRITICAL(&update_lock);
#elif MCU_VARIANT == MCU_NRF52
portENTER_CRITICAL();
#endif
uint8_t status = LoRa.modemStatus();
@ -938,6 +942,8 @@ void updateModemStatus() {
#if MCU_VARIANT == MCU_ESP32
portEXIT_CRITICAL(&update_lock);
#elif MCU_VARIANT == MCU_NRF52
portEXIT_CRITICAL();
#endif
if ((status & SIG_DETECT) == SIG_DETECT) { stat_signal_detected = true; } else { stat_signal_detected = false; }
@ -987,7 +993,7 @@ void checkModemStatus() {
if (millis()-last_status_update >= status_interval_ms) {
updateModemStatus();
#if MCU_VARIANT == MCU_ESP32
#if MCU_VARIANT == MCU_ESP32 || MCU_VARIANT == MCU_NRF52
util_samples[dcd_sample] = dcd;
dcd_sample = (dcd_sample+1)%DCD_SAMPLES;
if (dcd_sample % UTIL_UPDATE_INTERVAL == 0) {
@ -1028,6 +1034,12 @@ void validate_status() {
uint8_t F_POR = 0x00;
uint8_t F_BOR = 0x00;
uint8_t F_WDR = 0x01;
#elif MCU_VARIANT == MCU_NRF52
// TODO: Get NRF52 boot flags
uint8_t boot_flags = 0x02;
uint8_t F_POR = 0x00;
uint8_t F_BOR = 0x00;
uint8_t F_WDR = 0x01;
#endif
if (hw_ready || device_init_done) {
@ -1064,7 +1076,7 @@ void validate_status() {
if (eeprom_product_valid() && eeprom_model_valid() && eeprom_hwrev_valid()) {
if (eeprom_checksum_valid()) {
eeprom_ok = true;
if (sx1276_installed) {
if (modem_installed) {
#if PLATFORM == PLATFORM_ESP32
if (device_init()) {
hw_ready = true;
@ -1076,7 +1088,7 @@ void validate_status() {
#endif
} else {
hw_ready = false;
Serial.write("No SX1276/SX1278 radio module found\r\n");
Serial.write("No valid radio module found\r\n");
#if HAS_DISPLAY
if (disp_ready) {
device_init_done = true;
@ -1130,7 +1142,7 @@ void validate_status() {
}
}
#if MCU_VARIANT == MCU_ESP32
#if MCU_VARIANT == MCU_ESP32 || MCU_VARIANT == MCU_NRF52
#define _e 2.71828183
#define _S 10.0
float csma_slope(float u) { return (pow(_e,_S*u-_S/2.0))/(pow(_e,_S*u-_S/2.0)+1.0); }
@ -1152,6 +1164,21 @@ void loop() {
kiss_write_packet();
}
airtime_lock = false;
if (st_airtime_limit != 0.0 && airtime >= st_airtime_limit) airtime_lock = true;
if (lt_airtime_limit != 0.0 && longterm_airtime >= lt_airtime_limit) airtime_lock = true;
#elif MCU_VARIANT == MCU_NRF52
if (packet_ready) {
portENTER_CRITICAL();
last_rssi = LoRa.packetRssi();
last_snr_raw = LoRa.packetSnrRaw();
portEXIT_CRITICAL();
kiss_indicate_stat_rssi();
kiss_indicate_stat_snr();
kiss_write_packet();
}
airtime_lock = false;
if (st_airtime_limit != 0.0 && airtime >= st_airtime_limit) airtime_lock = true;
if (lt_airtime_limit != 0.0 && longterm_airtime >= lt_airtime_limit) airtime_lock = true;
@ -1160,7 +1187,7 @@ void loop() {
checkModemStatus();
if (!airtime_lock) {
if (queue_height > 0) {
#if MCU_VARIANT == MCU_ESP32
#if MCU_VARIANT == MCU_ESP32 || MCU_VARIANT == MCU_NRF52
long check_time = millis();
if (check_time > post_tx_yield_timeout) {
if (dcd_waiting && (check_time >= dcd_wait_until)) { dcd_waiting = false; }
@ -1217,7 +1244,7 @@ void loop() {
}
}
#if MCU_VARIANT == MCU_ESP32
#if MCU_VARIANT == MCU_ESP32 || MCU_VARIANT == MCU_NRF52
buffer_serial();
if (!fifo_isempty(&serialFIFO)) serial_poll();
#else
@ -1241,7 +1268,7 @@ volatile bool serial_polling = false;
void serial_poll() {
serial_polling = true;
#if MCU_VARIANT != MCU_ESP32
#if MCU_VARIANT != MCU_ESP32 && MCU_VARIANT != MCU_NRF52
while (!fifo_isempty_locked(&serialFIFO)) {
#else
while (!fifo_isempty(&serialFIFO)) {
@ -1275,12 +1302,12 @@ void buffer_serial() {
{
c++;
#if MCU_VARIANT != MCU_ESP32
#if MCU_VARIANT != MCU_ESP32 && MCU_VARIANT != MCU_NRF52
if (!fifo_isfull_locked(&serialFIFO)) {
fifo_push_locked(&serialFIFO, Serial.read());
}
#else
if (HAS_BLUETOOTH && bt_state == BT_STATE_CONNECTED) {
#elif HAS_BLUETOOTH
if (bt_state == BT_STATE_CONNECTED) {
if (!fifo_isfull(&serialFIFO)) {
fifo_push(&serialFIFO, SerialBT.read());
}
@ -1289,6 +1316,10 @@ void buffer_serial() {
fifo_push(&serialFIFO, Serial.read());
}
}
#else
if (!fifo_isfull(&serialFIFO)) {
fifo_push(&serialFIFO, Serial.read());
}
#endif
}

View File

@ -13,9 +13,15 @@
// You should have received a copy of the GNU General Public License
// along with this program. If not, see <https://www.gnu.org/licenses/>.
#include <EEPROM.h>
#include <stddef.h>
#include "Config.h"
#if HAS_EEPROM
#include <EEPROM.h>
#elif PLATFORM == PLATFORM_NRF52
#include "flash_nrf5x.h"
int written_bytes = 0;
#endif
#include <stddef.h>
#include "LoRa.h"
#include "ROM.h"
#include "Framing.h"
@ -34,8 +40,10 @@
#include "Power.h"
#endif
#if MCU_VARIANT == MCU_ESP32
#if MCU_VARIANT == MCU_ESP32 || MCU_VARIANT == MCU_NRF52
#include "Device.h"
#endif
#if MCU_VARIANT == MCU_ESP32
#include "soc/rtc_wdt.h"
#define ISR_VECT IRAM_ATTR
#else
@ -57,6 +65,8 @@ uint8_t boot_vector = 0x00;
}
#elif MCU_VARIANT == MCU_ESP32
// TODO: Get ESP32 boot flags
#elif MCU_VARIANT == MCU_NRF52
// TODO: Get NRF52 boot flags
#endif
#if HAS_NP == true
@ -175,6 +185,13 @@ uint8_t boot_vector = 0x00;
void led_tx_on() { digitalWrite(pin_led_tx, HIGH); }
void led_tx_off() { digitalWrite(pin_led_tx, LOW); }
#endif
#elif MCU_VARIANT == MCU_NRF52
#if BOARD_MODEL == BOARD_RAK4630
void led_rx_on() { digitalWrite(pin_led_rx, HIGH); }
void led_rx_off() { digitalWrite(pin_led_rx, LOW); }
void led_tx_on() { digitalWrite(pin_led_tx, HIGH); }
void led_tx_off() { digitalWrite(pin_led_tx, LOW); }
#endif
#endif
void hard_reset(void) {
@ -185,6 +202,8 @@ void hard_reset(void) {
}
#elif MCU_VARIANT == MCU_ESP32
ESP.restart();
#elif MCU_VARIANT == MCU_NRF52
// currently not possible to restart on this platform
#endif
}
@ -285,7 +304,7 @@ void led_indicate_warning(int cycles) {
}
led_rx_off();
}
#elif MCU_VARIANT == MCU_ESP32
#elif MCU_VARIANT == MCU_ESP32 || MCU_VARIANT == MCU_NRF52
#if HAS_NP == true
void led_indicate_info(int cycles) {
bool forever = (cycles == 0) ? true : false;
@ -375,6 +394,17 @@ unsigned long led_standby_ticks = 0;
unsigned long led_standby_wait = 1768;
unsigned long led_notready_wait = 150;
#endif
#elif MCU_VARIANT == MCU_NRF52
uint8_t led_standby_min = 200;
uint8_t led_standby_max = 255;
uint8_t led_notready_min = 0;
uint8_t led_notready_max = 255;
uint8_t led_notready_value = led_notready_min;
int8_t led_notready_direction = 0;
unsigned long led_notready_ticks = 0;
unsigned long led_standby_wait = 1768;
unsigned long led_notready_wait = 150;
#endif
unsigned long led_standby_value = led_standby_min;
@ -396,7 +426,7 @@ int8_t led_standby_direction = 0;
}
}
#elif MCU_VARIANT == MCU_ESP32
#elif MCU_VARIANT == MCU_ESP32 || MCU_VARIANT == MCU_NRF52
#if HAS_NP == true
void led_indicate_standby() {
led_standby_ticks++;
@ -504,7 +534,7 @@ int8_t led_standby_direction = 0;
led_rx_off();
}
}
#elif MCU_VARIANT == MCU_ESP32
#elif MCU_VARIANT == MCU_ESP32 || MCU_VARIANT == MCU_NRF52
#if HAS_NP == true
void led_indicate_not_ready() {
led_standby_ticks++;
@ -625,7 +655,11 @@ void kiss_indicate_stat_tx() {
}
void kiss_indicate_stat_rssi() {
uint8_t packet_rssi_val = (uint8_t)(last_rssi+rssi_offset);
#if MODEM == SX1276 || MODEM == SX1278
uint8_t packet_rssi_val = (uint8_t)(last_rssi+rssi_offset);
#elif MODEM == SX1262
uint8_t packet_rssi_val = (uint8_t)(last_rssi);
#endif
serial_write(FEND);
serial_write(CMD_STAT_RSSI);
escaped_serial_write(packet_rssi_val);
@ -799,7 +833,7 @@ void kiss_indicate_fbstate() {
serial_write(FEND);
}
#if MCU_VARIANT == MCU_ESP32
#if MCU_VARIANT == MCU_ESP32 || MCU_VARIANT == MCU_NRF52
void kiss_indicate_device_hash() {
serial_write(FEND);
serial_write(CMD_DEV_HASH);
@ -944,7 +978,7 @@ void setPreamble() {
}
void updateBitrate() {
#if MCU_VARIANT == MCU_ESP32
#if MCU_VARIANT == MCU_ESP32 || MCU_VARIANT == MCU_NRF52
if (radio_online) {
lora_symbol_rate = (float)lora_bw/(float)(pow(2, lora_sf));
lora_symbol_time_ms = (1.0/lora_symbol_rate)*1000.0;
@ -1058,8 +1092,21 @@ void promisc_disable() {
promisc = false;
}
#if !HAS_EEPROM && MCU_VARIANT == MCU_NRF52
uint8_t eeprom_read(uint32_t mapped_addr) {
uint8_t byte;
void* byte_ptr = &byte;
flash_nrf5x_read(byte_ptr, mapped_addr, 1);
return byte;
}
#endif
bool eeprom_info_locked() {
uint8_t lock_byte = EEPROM.read(eeprom_addr(ADDR_INFO_LOCK));
#if HAS_EEPROM
uint8_t lock_byte = EEPROM.read(eeprom_addr(ADDR_INFO_LOCK));
#elif MCU_VARIANT == MCU_NRF52
uint8_t lock_byte = eeprom_read(eeprom_addr(ADDR_INFO_LOCK));
#endif
if (lock_byte == INFO_LOCK_BYTE) {
return true;
} else {
@ -1069,21 +1116,33 @@ bool eeprom_info_locked() {
void eeprom_dump_info() {
for (int addr = ADDR_PRODUCT; addr <= ADDR_INFO_LOCK; addr++) {
uint8_t byte = EEPROM.read(eeprom_addr(addr));
#if HAS_EEPROM
uint8_t byte = EEPROM.read(eeprom_addr(addr));
#elif MCU_VARIANT == MCU_NRF52
uint8_t byte = eeprom_read(eeprom_addr(addr));
#endif
escaped_serial_write(byte);
}
}
void eeprom_dump_config() {
for (int addr = ADDR_CONF_SF; addr <= ADDR_CONF_OK; addr++) {
uint8_t byte = EEPROM.read(eeprom_addr(addr));
#if HAS_EEPROM
uint8_t byte = EEPROM.read(eeprom_addr(addr));
#elif MCU_VARIANT == MCU_NRF52
uint8_t byte = eeprom_read(eeprom_addr(addr));
#endif
escaped_serial_write(byte);
}
}
void eeprom_dump_all() {
for (int addr = 0; addr < EEPROM_RESERVED; addr++) {
uint8_t byte = EEPROM.read(eeprom_addr(addr));
#if HAS_EEPROM
uint8_t byte = EEPROM.read(eeprom_addr(addr));
#elif MCU_VARIANT == MCU_NRF52
uint8_t byte = eeprom_read(eeprom_addr(addr));
#endif
escaped_serial_write(byte);
}
}
@ -1103,6 +1162,22 @@ void eeprom_update(int mapped_addr, uint8_t byte) {
EEPROM.write(mapped_addr, byte);
EEPROM.commit();
}
#elif !HAS_EEPROM && MCU_VARIANT == MCU_NRF52
uint8_t read_byte;
void* read_byte_ptr = &read_byte;
void const * byte_ptr = &byte;
flash_nrf5x_read(read_byte_ptr, mapped_addr, 1);
if (read_byte != byte) {
flash_nrf5x_write(mapped_addr, byte_ptr, 1);
}
written_bytes++;
// flush the cache every 4 bytes to make sure everything is synced
if (written_bytes == 4) {
written_bytes = 0;
flash_nrf5x_flush();
}
#endif
}
@ -1123,7 +1198,11 @@ void eeprom_erase() {
}
bool eeprom_lock_set() {
if (EEPROM.read(eeprom_addr(ADDR_INFO_LOCK)) == INFO_LOCK_BYTE) {
#if HAS_EEPROM
if (EEPROM.read(eeprom_addr(ADDR_INFO_LOCK)) == INFO_LOCK_BYTE) {
#elif MCU_VARIANT == MCU_NRF52
if (eeprom_read(eeprom_addr(ADDR_INFO_LOCK)) == INFO_LOCK_BYTE) {
#endif
return true;
} else {
return false;
@ -1131,12 +1210,18 @@ bool eeprom_lock_set() {
}
bool eeprom_product_valid() {
uint8_t rval = EEPROM.read(eeprom_addr(ADDR_PRODUCT));
#if HAS_EEPROM
uint8_t rval = EEPROM.read(eeprom_addr(ADDR_PRODUCT));
#elif MCU_VARIANT == MCU_NRF52
uint8_t rval = eeprom_read(eeprom_addr(ADDR_PRODUCT));
#endif
#if PLATFORM == PLATFORM_AVR
if (rval == PRODUCT_RNODE || rval == PRODUCT_HMBRW) {
#elif 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) {
#elif PLATFORM == PLATFORM_NRF52
if (rval == PRODUCT_HMBRW) {
#else
if (false) {
#endif
@ -1147,7 +1232,11 @@ bool eeprom_product_valid() {
}
bool eeprom_model_valid() {
model = EEPROM.read(eeprom_addr(ADDR_MODEL));
#if HAS_EEPROM
model = EEPROM.read(eeprom_addr(ADDR_MODEL));
#elif MCU_VARIANT == MCU_NRF52
model = eeprom_read(eeprom_addr(ADDR_MODEL));
#endif
#if BOARD_MODEL == BOARD_RNODE
if (model == MODEL_A4 || model == MODEL_A9 || model == MODEL_FF || model == MODEL_FE) {
#elif BOARD_MODEL == BOARD_RNODE_NG_20
@ -1166,6 +1255,8 @@ bool eeprom_model_valid() {
if (model == MODEL_B4 || model == MODEL_B9) {
#elif BOARD_MODEL == BOARD_HELTEC32_V2
if (model == MODEL_C4 || model == MODEL_C9) {
#elif BOARD_MODEL == BOARD_RAK4630
if (model == MODEL_FF) {
#elif BOARD_MODEL == BOARD_HUZZAH32
if (model == MODEL_FF) {
#elif BOARD_MODEL == BOARD_GENERIC_ESP32
@ -1180,7 +1271,11 @@ bool eeprom_model_valid() {
}
bool eeprom_hwrev_valid() {
hwrev = EEPROM.read(eeprom_addr(ADDR_HW_REV));
#if HAS_EEPROM
hwrev = EEPROM.read(eeprom_addr(ADDR_HW_REV));
#elif MCU_VARIANT == MCU_NRF52
hwrev = eeprom_read(eeprom_addr(ADDR_HW_REV));
#endif
if (hwrev != 0x00 && hwrev != 0xFF) {
return true;
} else {
@ -1191,14 +1286,22 @@ bool eeprom_hwrev_valid() {
bool eeprom_checksum_valid() {
char *data = (char*)malloc(CHECKSUMMED_SIZE);
for (uint8_t i = 0; i < CHECKSUMMED_SIZE; i++) {
char byte = EEPROM.read(eeprom_addr(i));
#if HAS_EEPROM
char byte = EEPROM.read(eeprom_addr(i));
#elif MCU_VARIANT == MCU_NRF52
char byte = eeprom_read(eeprom_addr(i));
#endif
data[i] = byte;
}
unsigned char *hash = MD5::make_hash(data, CHECKSUMMED_SIZE);
bool checksum_valid = true;
for (uint8_t i = 0; i < 16; i++) {
uint8_t stored_chk_byte = EEPROM.read(eeprom_addr(ADDR_CHKSUM+i));
#if HAS_EEPROM
uint8_t stored_chk_byte = EEPROM.read(eeprom_addr(ADDR_CHKSUM+i));
#elif MCU_VARIANT == MCU_NRF52
uint8_t stored_chk_byte = eeprom_read(eeprom_addr(ADDR_CHKSUM+i));
#endif
uint8_t calced_chk_byte = (uint8_t)hash[i];
if (stored_chk_byte != calced_chk_byte) {
checksum_valid = false;
@ -1227,7 +1330,11 @@ void da_conf_save(uint8_t dadr) {
}
bool eeprom_have_conf() {
if (EEPROM.read(eeprom_addr(ADDR_CONF_OK)) == CONF_OK_BYTE) {
#if HAS_EEPROM
if (EEPROM.read(eeprom_addr(ADDR_CONF_OK)) == CONF_OK_BYTE) {
#elif MCU_VARIANT == MCU_NRF52
if (eeprom_read(eeprom_addr(ADDR_CONF_OK)) == CONF_OK_BYTE) {
#endif
return true;
} else {
return false;
@ -1236,11 +1343,19 @@ bool eeprom_have_conf() {
void eeprom_conf_load() {
if (eeprom_have_conf()) {
lora_sf = EEPROM.read(eeprom_addr(ADDR_CONF_SF));
lora_cr = EEPROM.read(eeprom_addr(ADDR_CONF_CR));
lora_txp = EEPROM.read(eeprom_addr(ADDR_CONF_TXP));
lora_freq = (uint32_t)EEPROM.read(eeprom_addr(ADDR_CONF_FREQ)+0x00) << 24 | (uint32_t)EEPROM.read(eeprom_addr(ADDR_CONF_FREQ)+0x01) << 16 | (uint32_t)EEPROM.read(eeprom_addr(ADDR_CONF_FREQ)+0x02) << 8 | (uint32_t)EEPROM.read(eeprom_addr(ADDR_CONF_FREQ)+0x03);
lora_bw = (uint32_t)EEPROM.read(eeprom_addr(ADDR_CONF_BW)+0x00) << 24 | (uint32_t)EEPROM.read(eeprom_addr(ADDR_CONF_BW)+0x01) << 16 | (uint32_t)EEPROM.read(eeprom_addr(ADDR_CONF_BW)+0x02) << 8 | (uint32_t)EEPROM.read(eeprom_addr(ADDR_CONF_BW)+0x03);
#if HAS_EEPROM
lora_sf = EEPROM.read(eeprom_addr(ADDR_CONF_SF));
lora_cr = EEPROM.read(eeprom_addr(ADDR_CONF_CR));
lora_txp = EEPROM.read(eeprom_addr(ADDR_CONF_TXP));
lora_freq = (uint32_t)EEPROM.read(eeprom_addr(ADDR_CONF_FREQ)+0x00) << 24 | (uint32_t)EEPROM.read(eeprom_addr(ADDR_CONF_FREQ)+0x01) << 16 | (uint32_t)EEPROM.read(eeprom_addr(ADDR_CONF_FREQ)+0x02) << 8 | (uint32_t)EEPROM.read(eeprom_addr(ADDR_CONF_FREQ)+0x03);
lora_bw = (uint32_t)EEPROM.read(eeprom_addr(ADDR_CONF_BW)+0x00) << 24 | (uint32_t)EEPROM.read(eeprom_addr(ADDR_CONF_BW)+0x01) << 16 | (uint32_t)EEPROM.read(eeprom_addr(ADDR_CONF_BW)+0x02) << 8 | (uint32_t)EEPROM.read(eeprom_addr(ADDR_CONF_BW)+0x03);
#elif MCU_VARIANT == MCU_NRF52
lora_sf = eeprom_read(eeprom_addr(ADDR_CONF_SF));
lora_cr = eeprom_read(eeprom_addr(ADDR_CONF_CR));
lora_txp = eeprom_read(eeprom_addr(ADDR_CONF_TXP));
lora_freq = (uint32_t)eeprom_read(eeprom_addr(ADDR_CONF_FREQ)+0x00) << 24 | (uint32_t)eeprom_read(eeprom_addr(ADDR_CONF_FREQ)+0x01) << 16 | (uint32_t)eeprom_read(eeprom_addr(ADDR_CONF_FREQ)+0x02) << 8 | (uint32_t)eeprom_read(eeprom_addr(ADDR_CONF_FREQ)+0x03);
lora_bw = (uint32_t)eeprom_read(eeprom_addr(ADDR_CONF_BW)+0x00) << 24 | (uint32_t)eeprom_read(eeprom_addr(ADDR_CONF_BW)+0x01) << 16 | (uint32_t)eeprom_read(eeprom_addr(ADDR_CONF_BW)+0x02) << 8 | (uint32_t)eeprom_read(eeprom_addr(ADDR_CONF_BW)+0x03);
#endif
}
}
@ -1327,7 +1442,7 @@ inline void fifo_flush(FIFOBuffer *f) {
f->head = f->tail;
}
#if MCU_VARIANT != MCU_ESP32
#if MCU_VARIANT != MCU_ESP32 && MCU_VARIANT != MCU_NRF52
static inline bool fifo_isempty_locked(const FIFOBuffer *f) {
bool result;
ATOMIC_BLOCK(ATOMIC_RESTORESTATE) {
@ -1409,7 +1524,7 @@ inline void fifo16_flush(FIFOBuffer16 *f) {
f->head = f->tail;
}
#if MCU_VARIANT != MCU_ESP32
#if MCU_VARIANT != MCU_ESP32 && MCU_VARIANT != MCU_NRF52
static inline bool fifo16_isempty_locked(const FIFOBuffer16 *f) {
bool result;
ATOMIC_BLOCK(ATOMIC_RESTORESTATE) {

View File

@ -1,3 +1,4 @@
board_manager:
additional_urls:
- https://raw.githubusercontent.com/espressif/arduino-esp32/gh-pages/package_esp32_index.json
- https://raw.githubusercontent.com/RAKwireless/RAKwireless-Arduino-BSP-Index/main/package_rakwireless_index.json

204
flash_cache.c Normal file
View File

@ -0,0 +1,204 @@
/*
* The MIT License (MIT)
*
* Copyright (c) 2019 Ha Thach for Adafruit Industries
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*/
#ifdef NRF52840_XXAA
#include <string.h>
#include "flash_cache.h"
#include "common_func.h"
#include "variant.h"
#include "wiring_digital.h"
//--------------------------------------------------------------------+
// MACRO TYPEDEF CONSTANT ENUM DECLARATION
//--------------------------------------------------------------------+
static inline uint32_t page_addr_of (uint32_t addr)
{
return addr & ~(FLASH_CACHE_SIZE - 1);
}
static inline uint32_t page_offset_of (uint32_t addr)
{
return addr & (FLASH_CACHE_SIZE - 1);
}
int flash_cache_write (flash_cache_t* fc, uint32_t dst, void const * src, uint32_t len)
{
uint8_t const * src8 = (uint8_t const *) src;
uint32_t remain = len;
// Program up to page boundary each loop
while ( remain )
{
uint32_t const page_addr = page_addr_of(dst);
uint32_t const offset = page_offset_of(dst);
uint32_t wr_bytes = FLASH_CACHE_SIZE - offset;
wr_bytes = min32(remain, wr_bytes);
// Page changes, flush old and update new cache
if ( page_addr != fc->cache_addr )
{
flash_cache_flush(fc);
fc->cache_addr = page_addr;
// read a whole page from flash
fc->read(fc->cache_buf, page_addr, FLASH_CACHE_SIZE);
}
memcpy(fc->cache_buf + offset, src8, wr_bytes);
// adjust for next run
src8 += wr_bytes;
remain -= wr_bytes;
dst += wr_bytes;
}
return len - remain;
}
void flash_cache_flush (flash_cache_t* fc)
{
if ( fc->cache_addr == FLASH_CACHE_INVALID_ADDR ) return;
// skip erase & program if verify() exists, and memory matches
if ( !(fc->verify && fc->verify(fc->cache_addr, fc->cache_buf, FLASH_CACHE_SIZE)) )
{
// indicator TODO allow to disable flash indicator
ledOn(LED_BUILTIN);
fc->erase(fc->cache_addr);
fc->program(fc->cache_addr, fc->cache_buf, FLASH_CACHE_SIZE);
ledOff(LED_BUILTIN);
}
fc->cache_addr = FLASH_CACHE_INVALID_ADDR;
}
int flash_cache_read (flash_cache_t* fc, void* dst, uint32_t addr, uint32_t count)
{
// there is no check for overflow / wraparound for dst + count, addr + count.
// this might be a useful thing to add for at least debug builds.
// overwrite with cache value if available
if ( (fc->cache_addr != FLASH_CACHE_INVALID_ADDR) && // cache is not valid
!(addr < fc->cache_addr && addr + count <= fc->cache_addr) && // starts before, ends before cache area
!(addr >= fc->cache_addr + FLASH_CACHE_SIZE) ) // starts after end of cache area
{
// This block is entered only when the read overlaps the cache area by at least one byte.
// If the read starts before the cache area, it's further guaranteed
// that count is large enough to cause the read to enter
// the cache area by at least 1 byte.
uint32_t dst_off = 0;
uint32_t src_off = 0;
if (addr < fc->cache_addr)
{
dst_off = fc->cache_addr - addr;
// Read the bytes prior to the cache address
fc->read(dst, addr, dst_off);
}
else
{
src_off = addr - fc->cache_addr;
}
// Thus, after the above code block executes:
// *** AT MOST ***, only one of src_off and dst_off are non-zero;
// (Both may be zero when the read starts at the start of the cache area.)
// dst_off corresponds to the number of bytes already read from PRIOR to the cache area.
// src_off corresponds to the byte offset to start reading at, from WITHIN the cache area.
// How many bytes to memcpy from flash area?
// Remember that, AT MOST, one of src_off and dst_off are non-zero.
// If src_off is non-zero, then dst_off is zero, representing that the
// read starts inside the cache. In this case:
// PARAM1 := FLASH_CACHE_SIZE - src_off == maximum possible bytes to read from cache
// PARAM2 := count
// Thus, taking the minimum of the two gives the number of bytes to read from cache,
// in the range [ 1 .. FLASH_CACHE_SIZE-src_off ].
// Else if dst_off is non-zero, then src_off is zero, representing that the
// read started prior to the cache area. In this case:
// PARAM1 := FLASH_CACHE_SIZE == full size of the cache
// PARAM2 := count - dst_off == total bytes requested, minus the count of those already read
// Because the original request is guaranteed to overlap the cache, the range for
// PARAM2 is ensured to be [ 1 .. count-1 ].
// Thus, taking the minimum of the two gives the number of bytes to read from cache,
// in the range [ 1 .. FLASH_CACHE_SIZE ]
// Else both src_off and dst_off are zero, representing that the read is starting
// exactly aligned to the cache.
// PARAM1 := FLASH_CACHE_SIZE
// PARAM2 := count
// Thus, taking the minimum of the two gives the number of bytes to read from cache,
// in the range [ 1 .. FLASH_CACHE_SIZE ]
//
// Therefore, in all cases, there is assurance that cache_bytes
// will be in the final range [1..FLASH_CACHE_SIZE].
uint32_t cache_bytes = minof(FLASH_CACHE_SIZE-src_off, count - dst_off);
// Use memcpy to read cached data into the buffer
// If src_off is non-zero, then dst_off is zero, representing that the
// read starts inside the cache. In this case:
// PARAM1 := dst
// PARAM2 := fc->cache_buf + src_off
// PARAM3 := cache_bytes
// Thus, all works as expected when starting in the midst of the cache.
// Else if dst_off is non-zero, then src_off is zero, representing that the
// read started prior to the cache. In this case:
// PARAM1 := dst + dst_off == destination offset by number of bytes already read
// PARAM2 := fc->cache_buf
// PARAM3 := cache_bytes
// Thus, all works as expected when starting prior to the cache.
// Else both src_off and dst_off are zero, representing that the read is starting
// exactly aligned to the cache.
// PARAM1 := dst
// PARAM2 := fc->cache_buf
// PARAM3 := cache_bytes
// Thus, all works as expected when starting exactly at the cache boundary
//
// Therefore, in all cases, there is assurance that cache_bytes
// will be in the final range [1..FLASH_CACHE_SIZE].
memcpy(dst + dst_off, fc->cache_buf + src_off, cache_bytes);
// Read any final bytes from flash
// As noted above, dst_off represents the count of bytes read prior to the cache
// while cache_bytes represents the count of bytes read from the cache;
// This code block is guaranteed to overlap the cache area by at least one byte.
// Thus, copied will correspond to the total bytes already copied,
// and is guaranteed to be in the range [ 1 .. count ].
uint32_t copied = dst_off + cache_bytes;
//
if ( copied < count )
{
fc->read(dst + copied, addr + copied, count - copied);
}
}
else
{
// not using the cache, so just forward to read from flash
fc->read(dst, addr, count);
}
return (int) count;
}
#endif

58
flash_cache.h Normal file
View File

@ -0,0 +1,58 @@
/*
* The MIT License (MIT)
*
* Copyright (c) 2019 Ha Thach for Adafruit Industries
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*/
#ifdef NRF52840_XXAA
#ifndef FLASH_CACHE_H_
#define FLASH_CACHE_H_
#include <stdint.h>
#include <stdbool.h>
#define FLASH_CACHE_SIZE 4096 // must be a erasable page size
#define FLASH_CACHE_INVALID_ADDR 0xffffffff
typedef struct
{
bool (*erase) (uint32_t addr);
uint32_t (*program) (uint32_t dst, void const * src, uint32_t len);
uint32_t (*read) (void* dst, uint32_t src, uint32_t len);
bool (*verify) (uint32_t addr, void const * buf, uint32_t len);
uint32_t cache_addr;
uint8_t* cache_buf;
} flash_cache_t;
#ifdef __cplusplus
extern "C" {
#endif
int flash_cache_write (flash_cache_t* fc, uint32_t dst, void const *src, uint32_t count);
void flash_cache_flush (flash_cache_t* fc);
int flash_cache_read (flash_cache_t* fc, void* dst, uint32_t addr, uint32_t count);
#ifdef __cplusplus
}
#endif
#endif /* FLASH_CACHE_H_ */
#endif

179
flash_nrf5x.c Normal file
View File

@ -0,0 +1,179 @@
/*
* The MIT License (MIT)
*
* Copyright (c) 2019 Ha Thach for Adafruit Industries
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*/
#ifdef NRF52840_XXAA
#include "flash_nrf5x.h"
#include "flash_cache.h"
#include "nrf_sdm.h"
#include "nrf_soc.h"
#include "delay.h"
#include "rtos.h"
#ifdef NRF52840_XXAA
#define BOOTLOADER_ADDR 0xF4000
#else
#define BOOTLOADER_ADDR 0x74000
#endif
// defined in linker script
extern uint32_t __flash_arduino_start[];
//extern uint32_t __flash_arduino_end[];
//--------------------------------------------------------------------+
// MACRO TYPEDEF CONSTANT ENUM DECLARATION
//--------------------------------------------------------------------+
static SemaphoreHandle_t _sem = NULL;
void flash_nrf5x_event_cb (uint32_t event)
{
// if (event != NRF_EVT_FLASH_OPERATION_SUCCESS) LOG_LV1("IFLASH", "Flash op Failed");
if ( _sem ) xSemaphoreGive(_sem);
}
// Flash Abstraction Layer
static bool fal_erase (uint32_t addr);
static uint32_t fal_program (uint32_t dst, void const * src, uint32_t len);
static uint32_t fal_read (void* dst, uint32_t src, uint32_t len);
static bool fal_verify (uint32_t addr, void const * buf, uint32_t len);
static uint8_t _cache_buffer[FLASH_CACHE_SIZE] __attribute__((aligned(4)));
static flash_cache_t _cache =
{
.erase = fal_erase,
.program = fal_program,
.read = fal_read,
.verify = fal_verify,
.cache_addr = FLASH_CACHE_INVALID_ADDR,
.cache_buf = _cache_buffer
};
//--------------------------------------------------------------------+
// Application API
//--------------------------------------------------------------------+
void flash_nrf5x_flush (void)
{
flash_cache_flush(&_cache);
}
int flash_nrf5x_write (uint32_t dst, void const * src, uint32_t len)
{
// Softdevice region
VERIFY(dst >= ((uint32_t) __flash_arduino_start), -1);
// Bootloader region
VERIFY(dst < BOOTLOADER_ADDR, -1);
return flash_cache_write(&_cache, dst, src, len);
}
int flash_nrf5x_read (void* dst, uint32_t src, uint32_t len)
{
return flash_cache_read(&_cache, dst, src, len);
}
bool flash_nrf5x_erase(uint32_t addr)
{
return fal_erase(addr);
}
//--------------------------------------------------------------------+
// HAL for caching
//--------------------------------------------------------------------+
static bool fal_erase (uint32_t addr)
{
// Init semaphore for first call
if ( _sem == NULL )
{
_sem = xSemaphoreCreateCounting(10, 0);
VERIFY(_sem);
}
// retry if busy
uint32_t err;
while ( NRF_ERROR_BUSY == (err = sd_flash_page_erase(addr / FLASH_NRF52_PAGE_SIZE)) )
{
delay(1);
}
VERIFY_STATUS(err, false);
// wait for async event if SD is enabled
uint8_t sd_en = 0;
(void) sd_softdevice_is_enabled(&sd_en);
if ( sd_en ) xSemaphoreTake(_sem, portMAX_DELAY);
return true;
}
static uint32_t fal_program (uint32_t dst, void const * src, uint32_t len)
{
// wait for async event if SD is enabled
uint8_t sd_en = 0;
(void) sd_softdevice_is_enabled(&sd_en);
uint32_t err;
// Somehow S140 v6.1.1 assert an error when writing a whole page
// https://devzone.nordicsemi.com/f/nordic-q-a/40088/sd_flash_write-cause-nrf_fault_id_sd_assert
// Workaround: write half page at a time.
#if NRF52832_XXAA
while ( NRF_ERROR_BUSY == (err = sd_flash_write((uint32_t*) dst, (uint32_t const *) src, len/4)) )
{
delay(1);
}
VERIFY_STATUS(err, 0);
if ( sd_en ) xSemaphoreTake(_sem, portMAX_DELAY);
#else
while ( NRF_ERROR_BUSY == (err = sd_flash_write((uint32_t*) dst, (uint32_t const *) src, len/8)) )
{
delay(1);
}
VERIFY_STATUS(err, 0);
if ( sd_en ) xSemaphoreTake(_sem, portMAX_DELAY);
while ( NRF_ERROR_BUSY == (err = sd_flash_write((uint32_t*) (dst+ len/2), (uint32_t const *) (src + len/2), len/8)) )
{
delay(1);
}
VERIFY_STATUS(err, 0);
if ( sd_en ) xSemaphoreTake(_sem, portMAX_DELAY);
#endif
return len;
}
static uint32_t fal_read (void* dst, uint32_t src, uint32_t len)
{
memcpy(dst, (void*) src, len);
return len;
}
static bool fal_verify (uint32_t addr, void const * buf, uint32_t len)
{
return 0 == memcmp((void*) addr, buf, len);
}
#endif

89
flash_nrf5x.h Normal file
View File

@ -0,0 +1,89 @@
/*
* The MIT License (MIT)
*
* Copyright (c) 2019 Ha Thach for Adafruit Industries
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*/
#ifdef NRF52840_XXAA
#ifndef FLASH_NRF52_H_
#define FLASH_NRF52_H_
#include "common_inc.h"
#define FLASH_NRF52_PAGE_SIZE 4096
#ifdef __cplusplus
extern "C" {
#endif
void flash_nrf5x_flush (void);
bool flash_nrf5x_erase(uint32_t addr);
int flash_nrf5x_write (uint32_t dst, void const * src, uint32_t len);
int flash_nrf5x_read (void* dst, uint32_t src, uint32_t len);
//--------------------------------------------------------------------+
// Write helper
//--------------------------------------------------------------------+
static inline int flash_nrf5x_write8 (uint32_t dst, uint8_t num)
{
return flash_nrf5x_write(dst, &num, sizeof(num));
}
static inline int flash_nrf5x_write16 (uint32_t dst, uint8_t num)
{
return flash_nrf5x_write(dst, &num, sizeof(num));
}
static inline int flash_nrf5x_write32 (uint32_t dst, uint8_t num)
{
return flash_nrf5x_write(dst, &num, sizeof(num));
}
//--------------------------------------------------------------------+
// Read helper
//--------------------------------------------------------------------+
static inline uint8_t flash_nrf5x_read8 (uint32_t src)
{
uint8_t num;
flash_nrf5x_read(&num, src, sizeof(num));
return num;
}
static inline uint16_t flash_nrf5x_read16 (uint32_t src)
{
uint16_t num;
flash_nrf5x_read(&num, src, sizeof(num));
return num;
}
static inline uint16_t flash_nrf5x_read32 (uint32_t src)
{
uint32_t num;
flash_nrf5x_read(&num, src, sizeof(num));
return num;
}
#ifdef __cplusplus
}
#endif
#endif /* FLASH_NRF52_H_ */
#endif