mirror of
https://github.com/markqvist/RNode_Firmware.git
synced 2024-10-01 03:15:39 -04:00
Get build building
This commit is contained in:
parent
c46ec5778d
commit
d01a4b293f
28
Config.h
28
Config.h
@ -17,29 +17,12 @@
|
||||
#define BOARD_LORA32_V2_1 0x37
|
||||
#define BOARD_SPIDEV 0x38
|
||||
|
||||
#define SERIAL_INTERRUPT 0x1
|
||||
#define SERIAL_POLLING 0x2
|
||||
|
||||
#define MODE_HOST 0x11
|
||||
#define MODE_TNC 0x12
|
||||
|
||||
#if defined(__AVR_ATmega1284P__)
|
||||
#define PLATFORM PLATFORM_AVR
|
||||
#define MCU_VARIANT MCU_1284P
|
||||
#define LIBRARY_TYPE LIBRARY_ARDUINO
|
||||
#elif defined(__AVR_ATmega2560__)
|
||||
#define PLATFORM PLATFORM_AVR
|
||||
#define MCU_VARIANT MCU_2560
|
||||
#define LIBRARY_TYPE LIBRARY_ARDUINO
|
||||
#elif defined(ESP32)
|
||||
#define PLATFORM PLATFORM_ESP32
|
||||
#define MCU_VARIANT MCU_ESP32
|
||||
#define LIBRARY_TYPE LIBRARY_ARDUINO
|
||||
#elif defined(__unix__)
|
||||
#define PLATFORM PLATFORM_LINUX
|
||||
#define MCU_VARIANT MCU_LINUX
|
||||
#define LIBRARY_TYPE LIBRARY_C
|
||||
#else
|
||||
#error "The firmware cannot be compiled for the selected MCU variant"
|
||||
#endif
|
||||
|
||||
#define MTU 500
|
||||
#define SINGLE_MTU 255
|
||||
#define HEADER_L 1
|
||||
@ -57,6 +40,7 @@
|
||||
const int pin_led_tx = 13;
|
||||
|
||||
#define BOARD_MODEL BOARD_RNODE
|
||||
#define SERIAL_EVENTS SERIAL_INTERRUPT
|
||||
|
||||
#define CONFIG_UART_BUFFER_SIZE 6144
|
||||
#define CONFIG_QUEUE_SIZE 6144
|
||||
@ -73,6 +57,7 @@
|
||||
const int pin_led_tx = 13;
|
||||
|
||||
#define BOARD_MODEL BOARD_HMBRW
|
||||
#define SERIAL_EVENTS SERIAL_INTERRUPT
|
||||
|
||||
#define CONFIG_UART_BUFFER_SIZE 768
|
||||
#define CONFIG_QUEUE_SIZE 5120
|
||||
@ -134,6 +119,8 @@
|
||||
#error An unsupported board was selected. Cannot compile RNode firmware.
|
||||
#endif
|
||||
|
||||
#define SERIAL_EVENTS SERIAL_POLLING
|
||||
|
||||
#define CONFIG_UART_BUFFER_SIZE 6144
|
||||
#define CONFIG_QUEUE_SIZE 6144
|
||||
#define CONFIG_QUEUE_MAX_LENGTH 200
|
||||
@ -152,6 +139,7 @@
|
||||
const int pin_led_tx = -1;
|
||||
|
||||
#define BOARD_MODEL BOARD_SPIDEV
|
||||
#define SERIAL_EVENTS SERIAL_POLLING
|
||||
|
||||
#define CONFIG_UART_BUFFER_SIZE 6144
|
||||
#define CONFIG_QUEUE_SIZE 6144
|
||||
|
2
LoRa.cpp
2
LoRa.cpp
@ -207,7 +207,7 @@ int LoRaClass::endPacket()
|
||||
#if LIBRARY_TYPE == LIBRARY_ARDUINO
|
||||
yield();
|
||||
#elif LIBRARY_TYPE == LIBRARY_C
|
||||
::sleep(1);
|
||||
::sleep(0);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
8
MD5.h
8
MD5.h
@ -1,13 +1,7 @@
|
||||
#ifndef MD5_h
|
||||
#define MD5_h
|
||||
|
||||
#include "Config.h"
|
||||
|
||||
#if LIBRARY_TYPE == LIBRARY_ARDUINO
|
||||
#include "Arduino.h"
|
||||
#elif LIBRARY_TYPE == LIBRARY_C
|
||||
#include <cstdlib>
|
||||
#endif
|
||||
#include "Platform.h"
|
||||
|
||||
/*
|
||||
* This is an OpenSSL-compatible implementation of the RSA Data Security,
|
||||
|
21
Makefile
21
Makefile
@ -10,11 +10,6 @@ prep-samd:
|
||||
arduino-cli core update-index --config-file arduino-cli.yaml
|
||||
arduino-cli core install adafruit:samd
|
||||
|
||||
prep-linux:
|
||||
mkdir -p bin
|
||||
mkdir -p obj
|
||||
|
||||
|
||||
firmware:
|
||||
arduino-cli compile --fqbn unsignedio:avr:rnode
|
||||
|
||||
@ -139,18 +134,22 @@ release-mega2560:
|
||||
cp build/arduino.avr.mega/RNode_Firmware.ino.hex Release/rnode_firmware_latest_m2560.hex
|
||||
rm -r build
|
||||
|
||||
.PHONY: clean prep-linux
|
||||
|
||||
clean:
|
||||
rm -Rf bin
|
||||
rm -Rf obj
|
||||
|
||||
obj/MD5.o: MD5.cpp MD5.h Config.h ROM.h Platform.h prep-linux
|
||||
obj/MD5.o: MD5.cpp MD5.h Platform.h
|
||||
mkdir -p obj
|
||||
$(CC) -c -o $@ $<
|
||||
|
||||
obj/LoRa.o: LoRa.cpp LoRa.h Platform.h prep-linux
|
||||
obj/LoRa.o: LoRa.cpp LoRa.h Platform.h
|
||||
mkdir -p obj
|
||||
$(CC) -c -o $@ $<
|
||||
|
||||
obj/RNode_firmware.o: RNode_firmware.ino Utilities.h Config.h LoRa.h ROM.h Framing.h MD5.h Platform.h prep-linux
|
||||
$(CC) -c -o $@ $<
|
||||
obj/RNode_Firmware.o: RNode_Firmware.ino Utilities.h Config.h LoRa.h ROM.h Framing.h MD5.h Platform.h
|
||||
mkdir -p obj
|
||||
$(CC) -c -o $@ -x c++ $<
|
||||
|
||||
bin/rnode: obj/RNode_Firmware.o obj/LoRa.o obj/MD5.o
|
||||
mkdir -p bin
|
||||
$(CC) -o $@ $^ -lstdc++
|
||||
|
@ -20,8 +20,12 @@
|
||||
// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
|
||||
// SOFTWARE.
|
||||
|
||||
#include <Arduino.h>
|
||||
#include <SPI.h>
|
||||
#include "Platform.h"
|
||||
|
||||
#if LIBRARY_TYPE == LIBRARY_ARDUINO
|
||||
#include <Arduino.h>
|
||||
#include <SPI.h>
|
||||
#endif
|
||||
#include "Utilities.h"
|
||||
|
||||
FIFOBuffer serialFIFO;
|
||||
@ -47,6 +51,16 @@ char sbuf[128];
|
||||
bool packet_ready = false;
|
||||
#endif
|
||||
|
||||
// Arduino C doesn't need pre-declarations to call functions that appear later,
|
||||
// but standard C does.
|
||||
void serial_interrupt_init();
|
||||
void validateStatus();
|
||||
void update_radio_lock();
|
||||
void transmit(uint16_t size);
|
||||
void buffer_serial();
|
||||
void serial_poll();
|
||||
|
||||
|
||||
void setup() {
|
||||
#if MCU_VARIANT == MCU_ESP32
|
||||
delay(500);
|
||||
@ -54,8 +68,10 @@ void setup() {
|
||||
Serial.setRxBufferSize(CONFIG_UART_BUFFER_SIZE);
|
||||
#endif
|
||||
|
||||
// Seed the PRNG
|
||||
randomSeed(analogRead(0));
|
||||
#if LIBRARY_TYPE == LIBRARY_ARDUINO
|
||||
// Seed the PRNG
|
||||
randomSeed(analogRead(0));
|
||||
#endif
|
||||
|
||||
// Initialise serial communication
|
||||
memset(serialBuffer, 0, sizeof(serialBuffer));
|
||||
@ -66,9 +82,11 @@ void setup() {
|
||||
|
||||
serial_interrupt_init();
|
||||
|
||||
// Configure input and output pins
|
||||
pinMode(pin_led_rx, OUTPUT);
|
||||
pinMode(pin_led_tx, OUTPUT);
|
||||
#if LIBRARY_TYPE == LIBRARY_ARDUINO
|
||||
// Configure input and output pins
|
||||
pinMode(pin_led_rx, OUTPUT);
|
||||
pinMode(pin_led_tx, OUTPUT);
|
||||
#endif
|
||||
|
||||
// Initialise buffers
|
||||
memset(pbuf, 0, sizeof(pbuf));
|
||||
@ -318,7 +336,7 @@ void flushQueue(void) {
|
||||
|
||||
uint16_t processed = 0;
|
||||
|
||||
#if MCU_VARIANT == MCU_ESP32
|
||||
#if SERIAL_EVENTS == SERIAL_POLLING
|
||||
while (!fifo16_isempty(&packet_starts)) {
|
||||
#else
|
||||
while (!fifo16_isempty_locked(&packet_starts)) {
|
||||
@ -683,13 +701,19 @@ void validateStatus() {
|
||||
uint8_t F_WDR = WDRF;
|
||||
#elif MCU_VARIANT == MCU_2560
|
||||
uint8_t boot_flags = OPTIBOOT_MCUSR;
|
||||
if (boot_flags == 0x00) boot_flags = 0x03;
|
||||
if (boot_flags == 0x00) boot_flags = START_FROM_BROWNOUT;
|
||||
uint8_t F_POR = PORF;
|
||||
uint8_t F_BOR = BORF;
|
||||
uint8_t F_WDR = WDRF;
|
||||
#elif MCU_VARIANT == MCU_ESP32
|
||||
// TODO: Get ESP32 boot flags
|
||||
uint8_t boot_flags = 0x02;
|
||||
uint8_t boot_flags = START_FROM_POWERON;
|
||||
uint8_t F_POR = 0x00;
|
||||
uint8_t F_BOR = 0x00;
|
||||
uint8_t F_WDR = 0x01;
|
||||
#elif MCU_VARIANT == MCU_LINUX
|
||||
// Linux build always works like a clean boot.
|
||||
uint8_t boot_flags = START_FROM_POWERON;
|
||||
uint8_t F_POR = 0x00;
|
||||
uint8_t F_BOR = 0x00;
|
||||
uint8_t F_WDR = 0x01;
|
||||
@ -707,7 +731,7 @@ void validateStatus() {
|
||||
}
|
||||
|
||||
if (boot_vector == START_FROM_BOOTLOADER || boot_vector == START_FROM_POWERON) {
|
||||
if (eeprom_lock_set()) {
|
||||
if (eeprom_info_locked()) {
|
||||
if (eeprom_product_valid() && eeprom_model_valid() && eeprom_hwrev_valid()) {
|
||||
if (eeprom_checksum_valid()) {
|
||||
hw_ready = true;
|
||||
@ -775,7 +799,7 @@ void loop() {
|
||||
}
|
||||
}
|
||||
|
||||
#if MCU_VARIANT == MCU_ESP32
|
||||
#if SERIAL_EVENTS == SERIAL_POLLING
|
||||
buffer_serial();
|
||||
if (!fifo_isempty(&serialFIFO)) serial_poll();
|
||||
#else
|
||||
@ -787,7 +811,7 @@ volatile bool serial_polling = false;
|
||||
void serial_poll() {
|
||||
serial_polling = true;
|
||||
|
||||
#if MCU_VARIANT != MCU_ESP32
|
||||
#if SERIAL_EVENTS == SERIAL_INTERRUPT
|
||||
while (!fifo_isempty_locked(&serialFIFO)) {
|
||||
#else
|
||||
while (!fifo_isempty(&serialFIFO)) {
|
||||
@ -812,7 +836,7 @@ void buffer_serial() {
|
||||
while (c < MAX_CYCLES && Serial.available()) {
|
||||
c++;
|
||||
|
||||
#if MCU_VARIANT != MCU_ESP32
|
||||
#if SERIAL_EVENTS == SERIAL_INTERRUPT
|
||||
if (!fifo_isfull_locked(&serialFIFO)) {
|
||||
fifo_push_locked(&serialFIFO, Serial.read());
|
||||
}
|
||||
@ -853,8 +877,8 @@ void serial_interrupt_init() {
|
||||
|
||||
TIMSK3 = _BV(ICIE3);
|
||||
|
||||
#elif MCU_VARIANT == MCU_ESP32
|
||||
// No interrupt-based polling on ESP32
|
||||
#else
|
||||
// No interrupt-based polling on other MCUs.
|
||||
#endif
|
||||
|
||||
}
|
||||
|
229
Utilities.h
229
Utilities.h
@ -1,4 +1,6 @@
|
||||
#include <EEPROM.h>
|
||||
#if LIBRARY_TYPE == LIBRARY_ARDUINO
|
||||
#include <EEPROM.h>
|
||||
#endif
|
||||
#include <stddef.h>
|
||||
#include "Config.h"
|
||||
#include "LoRa.h"
|
||||
@ -6,6 +8,81 @@
|
||||
#include "Framing.h"
|
||||
#include "MD5.h"
|
||||
|
||||
#if LIBRARY_TYPE == LIBRARY_C
|
||||
#include <time.h>
|
||||
// We need a delay()
|
||||
void delay(int ms) {
|
||||
struct timespec interval;
|
||||
interval.tv_sec = ms / 1000;
|
||||
interval.tv_nsec = (ms % 1000) * 1000 * 1000;
|
||||
// TODO: handle signals interrupting sleep
|
||||
nanosleep(&interval, NULL);
|
||||
}
|
||||
|
||||
// And millis()
|
||||
struct timespec millis_base;
|
||||
uint32_t millis() {
|
||||
// Time since first call is close enough.
|
||||
static bool base_set(false);
|
||||
if (!base_set) {
|
||||
if (clock_gettime(CLOCK_MONOTONIC, &millis_base)) {
|
||||
exit(1);
|
||||
}
|
||||
base_set = true;
|
||||
}
|
||||
struct timespec now;
|
||||
if (clock_gettime(CLOCK_MONOTONIC, &now)) {
|
||||
exit(1);
|
||||
}
|
||||
return (now.tv_sec - millis_base.tv_sec) * 1000 + (now.tv_nsec - millis_base.tv_nsec)/(1000*1000);
|
||||
}
|
||||
|
||||
// We also need a Serial
|
||||
class SerialClass {
|
||||
public:
|
||||
const char* fifoPath = "rnode_socket";
|
||||
void begin(int baud) {
|
||||
int status = mkfifo(fifoPath, 0666);
|
||||
if (status) {
|
||||
perror("Making fifo failed");
|
||||
exit(1);
|
||||
}
|
||||
// TODO: Need a bidirectional thing here: openpty???
|
||||
_fd = open(fifoPath, O_RDWR);
|
||||
if (_fd < 0) {
|
||||
perror("could not open fifo");
|
||||
exit(1);
|
||||
}
|
||||
}
|
||||
// Be truthy if connected
|
||||
operator bool() {
|
||||
return _fd > 0;
|
||||
}
|
||||
void write(int b) {
|
||||
ssize_t written = ::write(_fd,
|
||||
}
|
||||
void write(const char* data) {
|
||||
throw std::runtime_error("Unimplemented");
|
||||
}
|
||||
bool available() {
|
||||
throw std::runtime_error("Unimplemented");
|
||||
}
|
||||
uint8_t read() {
|
||||
throw std::runtime_error("Unimplemented");
|
||||
}
|
||||
protected:
|
||||
int _fd = -1;
|
||||
};
|
||||
SerialClass Serial;
|
||||
|
||||
// And random(below);
|
||||
int random(int below) {
|
||||
return rand() % below;
|
||||
}
|
||||
|
||||
|
||||
#endif
|
||||
|
||||
#if MCU_VARIANT == MCU_ESP32
|
||||
#include "soc/rtc_wdt.h"
|
||||
#define ISR_VECT IRAM_ATTR
|
||||
@ -68,7 +145,15 @@ uint8_t boot_vector = 0x00;
|
||||
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
|
||||
#elif MCU_VARIANT == MCU_LINUX
|
||||
#if BOARD_MODEL == BOARD_SPIDEV
|
||||
// No LEDs on this board. SPI only.
|
||||
void led_rx_on() { }
|
||||
void led_rx_off() { }
|
||||
void led_tx_on() { }
|
||||
void led_tx_off() { }
|
||||
#endif
|
||||
#endif
|
||||
|
||||
void hard_reset(void) {
|
||||
@ -79,23 +164,27 @@ void hard_reset(void) {
|
||||
}
|
||||
#elif MCU_VARIANT == MCU_ESP32
|
||||
ESP.restart();
|
||||
#elif MCU_VARIANT == MCU_LINUX
|
||||
// TODO: re-exec ourselves?
|
||||
// For now just quit.
|
||||
exit(0);
|
||||
#endif
|
||||
}
|
||||
|
||||
void led_indicate_error(int cycles) {
|
||||
bool forever = (cycles == 0) ? true : false;
|
||||
cycles = forever ? 1 : cycles;
|
||||
while(cycles > 0) {
|
||||
digitalWrite(pin_led_rx, HIGH);
|
||||
digitalWrite(pin_led_tx, LOW);
|
||||
delay(100);
|
||||
digitalWrite(pin_led_rx, LOW);
|
||||
digitalWrite(pin_led_tx, HIGH);
|
||||
delay(100);
|
||||
if (!forever) cycles--;
|
||||
}
|
||||
led_rx_off();
|
||||
while(cycles > 0) {
|
||||
led_rx_on();
|
||||
led_tx_off();
|
||||
delay(100);
|
||||
led_rx_off();
|
||||
led_tx_on();
|
||||
delay(100);
|
||||
if (!forever) cycles--;
|
||||
}
|
||||
led_rx_off();
|
||||
led_tx_off();
|
||||
}
|
||||
|
||||
void led_indicate_boot_error() {
|
||||
@ -112,7 +201,7 @@ void led_indicate_boot_error() {
|
||||
void led_indicate_warning(int cycles) {
|
||||
bool forever = (cycles == 0) ? true : false;
|
||||
cycles = forever ? 1 : cycles;
|
||||
digitalWrite(pin_led_tx, HIGH);
|
||||
led_tx_on();
|
||||
while(cycles > 0) {
|
||||
led_tx_off();
|
||||
delay(100);
|
||||
@ -123,7 +212,7 @@ void led_indicate_warning(int cycles) {
|
||||
led_tx_off();
|
||||
}
|
||||
|
||||
#if MCU_VARIANT == MCU_1284P || MCU_VARIANT == MCU_2560
|
||||
#if MCU_VARIANT == MCU_1284P || MCU_VARIANT == MCU_2560 || MCU_VARIANT == MCU_LINUX
|
||||
void led_indicate_info(int cycles) {
|
||||
bool forever = (cycles == 0) ? true : false;
|
||||
cycles = forever ? 1 : cycles;
|
||||
@ -179,8 +268,9 @@ void led_indicate_warning(int cycles) {
|
||||
#endif
|
||||
#endif
|
||||
|
||||
|
||||
unsigned long led_standby_ticks = 0;
|
||||
#if MCU_VARIANT == MCU_1284P || MCU_VARIANT == MCU_2560 || MCU_VARIANT == MCU_ESP32
|
||||
unsigned long led_standby_ticks = 0;
|
||||
#endif
|
||||
#if MCU_VARIANT == MCU_1284P || MCU_VARIANT == MCU_2560
|
||||
uint8_t led_standby_min = 1;
|
||||
uint8_t led_standby_max = 40;
|
||||
@ -196,8 +286,10 @@ unsigned long led_standby_ticks = 0;
|
||||
unsigned long led_standby_wait = 1768;
|
||||
unsigned long led_notready_wait = 150;
|
||||
#endif
|
||||
uint8_t led_standby_value = led_standby_min;
|
||||
int8_t led_standby_direction = 0;
|
||||
#if MCU_VARIANT == MCU_1284P || MCU_VARIANT == MCU_2560 || MCU_VARIANT == MCU_ESP32
|
||||
uint8_t led_standby_value = led_standby_min;
|
||||
int8_t led_standby_direction = 0;
|
||||
#endif
|
||||
|
||||
#if MCU_VARIANT == MCU_1284P || MCU_VARIANT == MCU_2560
|
||||
void led_indicate_standby() {
|
||||
@ -243,6 +335,9 @@ int8_t led_standby_direction = 0;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
#elif MCU_VARIANT == MCU_LINUX
|
||||
// No LEDs available.
|
||||
void led_indicate_standby() {}
|
||||
#endif
|
||||
|
||||
#if MCU_VARIANT == MCU_1284P || MCU_VARIANT == MCU_2560
|
||||
@ -289,6 +384,9 @@ int8_t led_standby_direction = 0;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
#elif MCU_VARIANT == MCU_LINUX
|
||||
// No LEDs available.
|
||||
void led_indicate_not_ready() {}
|
||||
#endif
|
||||
|
||||
void escapedSerialWrite(uint8_t byte) {
|
||||
@ -551,8 +649,16 @@ void promisc_disable() {
|
||||
promisc = false;
|
||||
}
|
||||
|
||||
uint8_t eeprom_read(uint8_t addr) {
|
||||
#if MCU_VARIANT == MCU_LINUX
|
||||
return 0;
|
||||
#else
|
||||
return EEPROM.read(eeprom_addr(addr));
|
||||
#endif
|
||||
}
|
||||
|
||||
bool eeprom_info_locked() {
|
||||
uint8_t lock_byte = EEPROM.read(eeprom_addr(ADDR_INFO_LOCK));
|
||||
uint8_t lock_byte = eeprom_read(ADDR_INFO_LOCK);
|
||||
if (lock_byte == INFO_LOCK_BYTE) {
|
||||
return true;
|
||||
} else {
|
||||
@ -560,34 +666,6 @@ 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));
|
||||
escapedSerialWrite(byte);
|
||||
}
|
||||
}
|
||||
|
||||
void eeprom_dump_config() {
|
||||
for (int addr = ADDR_CONF_SF; addr <= ADDR_CONF_OK; addr++) {
|
||||
uint8_t byte = EEPROM.read(eeprom_addr(addr));
|
||||
escapedSerialWrite(byte);
|
||||
}
|
||||
}
|
||||
|
||||
void eeprom_dump_all() {
|
||||
for (int addr = 0; addr < EEPROM_RESERVED; addr++) {
|
||||
uint8_t byte = EEPROM.read(eeprom_addr(addr));
|
||||
escapedSerialWrite(byte);
|
||||
}
|
||||
}
|
||||
|
||||
void kiss_dump_eeprom() {
|
||||
Serial.write(FEND);
|
||||
Serial.write(CMD_ROM_READ);
|
||||
eeprom_dump_all();
|
||||
Serial.write(FEND);
|
||||
}
|
||||
|
||||
void eeprom_update(int mapped_addr, uint8_t byte) {
|
||||
#if MCU_VARIANT == MCU_1284P || MCU_VARIANT == MCU_2560
|
||||
EEPROM.update(mapped_addr, byte);
|
||||
@ -597,7 +675,6 @@ void eeprom_update(int mapped_addr, uint8_t byte) {
|
||||
EEPROM.commit();
|
||||
}
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
void eeprom_write(uint8_t addr, uint8_t byte) {
|
||||
@ -615,16 +692,36 @@ void eeprom_erase() {
|
||||
hard_reset();
|
||||
}
|
||||
|
||||
bool eeprom_lock_set() {
|
||||
if (EEPROM.read(eeprom_addr(ADDR_INFO_LOCK)) == INFO_LOCK_BYTE) {
|
||||
return true;
|
||||
} else {
|
||||
return false;
|
||||
void eeprom_dump_info() {
|
||||
for (int addr = ADDR_PRODUCT; addr <= ADDR_INFO_LOCK; addr++) {
|
||||
uint8_t byte = eeprom_read(addr);
|
||||
escapedSerialWrite(byte);
|
||||
}
|
||||
}
|
||||
|
||||
void eeprom_dump_config() {
|
||||
for (int addr = ADDR_CONF_SF; addr <= ADDR_CONF_OK; addr++) {
|
||||
uint8_t byte = eeprom_read(addr);
|
||||
escapedSerialWrite(byte);
|
||||
}
|
||||
}
|
||||
|
||||
void eeprom_dump_all() {
|
||||
for (int addr = 0; addr < EEPROM_RESERVED; addr++) {
|
||||
uint8_t byte = eeprom_read(addr);
|
||||
escapedSerialWrite(byte);
|
||||
}
|
||||
}
|
||||
|
||||
void kiss_dump_eeprom() {
|
||||
Serial.write(FEND);
|
||||
Serial.write(CMD_ROM_READ);
|
||||
eeprom_dump_all();
|
||||
Serial.write(FEND);
|
||||
}
|
||||
|
||||
bool eeprom_product_valid() {
|
||||
uint8_t rval = EEPROM.read(eeprom_addr(ADDR_PRODUCT));
|
||||
uint8_t rval = eeprom_read(ADDR_PRODUCT);
|
||||
|
||||
#if PLATFORM == PLATFORM_AVR
|
||||
if (rval == PRODUCT_RNODE || rval == PRODUCT_HMBRW) {
|
||||
@ -640,7 +737,7 @@ bool eeprom_product_valid() {
|
||||
}
|
||||
|
||||
bool eeprom_model_valid() {
|
||||
model = EEPROM.read(eeprom_addr(ADDR_MODEL));
|
||||
model = eeprom_read(ADDR_MODEL);
|
||||
#if BOARD_MODEL == BOARD_RNODE
|
||||
if (model == MODEL_A4 || model == MODEL_A9) {
|
||||
#elif BOARD_MODEL == BOARD_HMBRW
|
||||
@ -665,7 +762,7 @@ bool eeprom_model_valid() {
|
||||
}
|
||||
|
||||
bool eeprom_hwrev_valid() {
|
||||
hwrev = EEPROM.read(eeprom_addr(ADDR_HW_REV));
|
||||
hwrev = eeprom_read(ADDR_HW_REV);
|
||||
if (hwrev != 0x00 && hwrev != 0xFF) {
|
||||
return true;
|
||||
} else {
|
||||
@ -676,14 +773,14 @@ 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));
|
||||
char byte = eeprom_read(i);
|
||||
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));
|
||||
uint8_t stored_chk_byte = eeprom_read(ADDR_CHKSUM+i);
|
||||
uint8_t calced_chk_byte = (uint8_t)hash[i];
|
||||
if (stored_chk_byte != calced_chk_byte) {
|
||||
checksum_valid = false;
|
||||
@ -696,7 +793,7 @@ bool eeprom_checksum_valid() {
|
||||
}
|
||||
|
||||
bool eeprom_have_conf() {
|
||||
if (EEPROM.read(eeprom_addr(ADDR_CONF_OK)) == CONF_OK_BYTE) {
|
||||
if (eeprom_read(ADDR_CONF_OK) == CONF_OK_BYTE) {
|
||||
return true;
|
||||
} else {
|
||||
return false;
|
||||
@ -705,11 +802,11 @@ 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);
|
||||
lora_sf = eeprom_read(ADDR_CONF_SF);
|
||||
lora_cr = eeprom_read(ADDR_CONF_CR);
|
||||
lora_txp = eeprom_read(ADDR_CONF_TXP);
|
||||
lora_freq = (uint32_t)eeprom_read(ADDR_CONF_FREQ+0x00) << 24 | (uint32_t)eeprom_read(ADDR_CONF_FREQ+0x01) << 16 | (uint32_t)eeprom_read(ADDR_CONF_FREQ+0x02) << 8 | (uint32_t)eeprom_read(ADDR_CONF_FREQ+0x03);
|
||||
lora_bw = (uint32_t)eeprom_read(ADDR_CONF_BW+0x00) << 24 | (uint32_t)eeprom_read(ADDR_CONF_BW+0x01) << 16 | (uint32_t)eeprom_read(ADDR_CONF_BW+0x02) << 8 | (uint32_t)eeprom_read(ADDR_CONF_BW+0x03);
|
||||
}
|
||||
}
|
||||
|
||||
@ -784,7 +881,7 @@ inline void fifo_flush(FIFOBuffer *f) {
|
||||
f->head = f->tail;
|
||||
}
|
||||
|
||||
#if MCU_VARIANT != MCU_ESP32
|
||||
#if SERIAL_EVENTS == SERIAL_INTERRUPT
|
||||
static inline bool fifo_isempty_locked(const FIFOBuffer *f) {
|
||||
bool result;
|
||||
ATOMIC_BLOCK(ATOMIC_RESTORESTATE) {
|
||||
@ -866,7 +963,7 @@ inline void fifo16_flush(FIFOBuffer16 *f) {
|
||||
f->head = f->tail;
|
||||
}
|
||||
|
||||
#if MCU_VARIANT != MCU_ESP32
|
||||
#if SERIAL_EVENTS == SERIAL_INTERRUPT
|
||||
static inline bool fifo16_isempty_locked(const FIFOBuffer16 *f) {
|
||||
bool result;
|
||||
ATOMIC_BLOCK(ATOMIC_RESTORESTATE) {
|
||||
|
Loading…
Reference in New Issue
Block a user