mirror of
https://github.com/markqvist/RNode_Firmware.git
synced 2024-10-01 03:15:39 -04:00
Don't talk to modem when not begun
Indirect debug prints Implement Linux EEPROM from file Make EEPROM-flashable Explain how to flash on startup
This commit is contained in:
parent
04c8523619
commit
910b8b0821
3
Config.h
3
Config.h
@ -15,7 +15,6 @@
|
||||
#define BOARD_GENERIC_ESP32 0x35
|
||||
#define BOARD_LORA32_V2_0 0x36
|
||||
#define BOARD_LORA32_V2_1 0x37
|
||||
#define BOARD_SPIDEV 0x38
|
||||
|
||||
#define SERIAL_INTERRUPT 0x1
|
||||
#define SERIAL_POLLING 0x2
|
||||
@ -138,7 +137,7 @@
|
||||
const int pin_led_rx = -1;
|
||||
const int pin_led_tx = -1;
|
||||
|
||||
#define BOARD_MODEL BOARD_SPIDEV
|
||||
#define BOARD_MODEL BOARD_HMBRW
|
||||
#define SERIAL_EVENTS SERIAL_POLLING
|
||||
|
||||
#define CONFIG_UART_BUFFER_SIZE 6144
|
||||
|
32
LoRa.cpp
32
LoRa.cpp
@ -88,7 +88,8 @@ LoRaClass::LoRaClass() :
|
||||
_frequency(0),
|
||||
_packetIndex(0),
|
||||
_implicitHeaderMode(0),
|
||||
_onReceive(NULL)
|
||||
_onReceive(NULL),
|
||||
_spiBegun(false)
|
||||
{
|
||||
#if LIBRARY_TYPE == LIBRARY_ARDUINO
|
||||
// overide Stream timeout value
|
||||
@ -118,7 +119,7 @@ int LoRaClass::begin(long frequency)
|
||||
digitalWrite(_reset, HIGH);
|
||||
delay(10);
|
||||
#endif
|
||||
// TODO: No reset pin hooked up on BOARD_SPIDEV
|
||||
// TODO: No reset pin hooked up on Linux
|
||||
}
|
||||
|
||||
#if LIBRARY_TYPE == LIBRARY_ARDUINO
|
||||
@ -126,13 +127,19 @@ int LoRaClass::begin(long frequency)
|
||||
SPI.begin();
|
||||
#elif LIBRARY_TYPE == LIBRARY_C
|
||||
const char* spi_filename = "/dev/spidev0.0";
|
||||
std::cerr << "Opening SPI device " << spi_filename << std::endl;
|
||||
_fd = open(spi_filename, O_RDWR);
|
||||
// We need to be re-entrant for restart
|
||||
if (_fd <= 0) {
|
||||
perror("could not open SPI device");
|
||||
exit(1);
|
||||
std::cerr << "Opening SPI device " << spi_filename << std::endl;
|
||||
_fd = open(spi_filename, O_RDWR);
|
||||
if (_fd <= 0) {
|
||||
perror("could not open SPI device");
|
||||
exit(1);
|
||||
}
|
||||
} else {
|
||||
std::cerr << "Skipping LoRa SPI reinitialization" << std::endl;
|
||||
}
|
||||
#endif
|
||||
_spiBegun = true;
|
||||
|
||||
// check version
|
||||
uint8_t version = readRegister(REG_VERSION);
|
||||
@ -167,8 +174,13 @@ int LoRaClass::begin(long frequency)
|
||||
|
||||
void LoRaClass::end()
|
||||
{
|
||||
// put in sleep mode
|
||||
this->sleep();
|
||||
// We need to be safe to call when the main loop is shutting down because
|
||||
// it's in a bad state, even if we ourselves haven't been begun yet. We can't
|
||||
// safely talk to the modem if the SPI link isn't begun, though.
|
||||
if (_spiBegun) {
|
||||
// put in sleep mode
|
||||
this->sleep();
|
||||
}
|
||||
|
||||
#if LIBRARY_TYPE == LIBRARY_ARDUINO
|
||||
// stop SPI
|
||||
@ -179,6 +191,7 @@ void LoRaClass::end()
|
||||
_fd = -1;
|
||||
}
|
||||
#endif
|
||||
_spiBegun = false;
|
||||
}
|
||||
|
||||
int LoRaClass::beginPacket(int implicitHeader)
|
||||
@ -706,6 +719,9 @@ uint8_t ISR_VECT LoRaClass::singleTransfer(uint8_t address, uint8_t value)
|
||||
int status;
|
||||
|
||||
std::cerr << "Access SPI at " << _fd << std::endl;
|
||||
if (_fd <= 0) {
|
||||
throw std::runtime_error("Accessing SPI device without begin()!");
|
||||
}
|
||||
|
||||
// Configure SPI speed and mode to match settings
|
||||
status = ioctl(_fd, SPI_IOC_WR_MODE, &_spiSettings.mode);
|
||||
|
1
LoRa.h
1
LoRa.h
@ -133,6 +133,7 @@ private:
|
||||
int _packetIndex;
|
||||
int _implicitHeaderMode;
|
||||
void (*_onReceive)(int);
|
||||
bool _spiBegun;
|
||||
#if LIBRARY_TYPE == LIBRARY_C
|
||||
int _fd;
|
||||
#endif
|
||||
|
12
Makefile
12
Makefile
@ -137,19 +137,21 @@ release-mega2560:
|
||||
clean:
|
||||
rm -Rf bin
|
||||
rm -Rf obj
|
||||
|
||||
|
||||
CFLAGS += -g
|
||||
|
||||
obj/MD5.o: MD5.cpp MD5.h Platform.h
|
||||
mkdir -p obj
|
||||
$(CC) -c -o $@ $<
|
||||
$(CC) $(CFLAGS) -c -o $@ $<
|
||||
|
||||
obj/LoRa.o: LoRa.cpp LoRa.h Platform.h
|
||||
mkdir -p obj
|
||||
$(CC) -c -o $@ $<
|
||||
$(CC) $(CFLAGS) -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++ $<
|
||||
$(CC) $(CFLAGS) -c -o $@ -x c++ $<
|
||||
|
||||
bin/rnode: obj/RNode_Firmware.o obj/LoRa.o obj/MD5.o
|
||||
mkdir -p bin
|
||||
$(CC) -o $@ $^ -lstdc++ -lutil
|
||||
$(CC) $(CFLAGS) -o $@ $^ -lstdc++ -lutil
|
||||
|
@ -64,9 +64,8 @@ void serial_poll();
|
||||
void setup() {
|
||||
#if MCU_VARIANT == MCU_ESP32
|
||||
delay(500);
|
||||
EEPROM.begin(EEPROM_SIZE);
|
||||
Serial.setRxBufferSize(CONFIG_UART_BUFFER_SIZE);
|
||||
#endif
|
||||
eeprom_open(EEPROM_SIZE);
|
||||
|
||||
#if LIBRARY_TYPE == LIBRARY_ARDUINO
|
||||
// Seed the PRNG
|
||||
@ -79,6 +78,10 @@ void setup() {
|
||||
|
||||
Serial.begin(serial_baudrate);
|
||||
while (!Serial);
|
||||
|
||||
#if MCU_VARIANT == MCU_ESP32
|
||||
Serial.setRxBufferSize(CONFIG_UART_BUFFER_SIZE);
|
||||
#endif
|
||||
|
||||
serial_interrupt_init();
|
||||
|
||||
@ -726,7 +729,7 @@ void validateStatus() {
|
||||
} else if (boot_flags & (1<<F_WDR)) {
|
||||
boot_vector = START_FROM_BOOTLOADER;
|
||||
} else {
|
||||
Serial.write("Error, indeterminate boot vector\r\n");
|
||||
debug("Error, indeterminate boot vector\r\n");
|
||||
led_indicate_boot_error();
|
||||
}
|
||||
|
||||
@ -741,16 +744,21 @@ void validateStatus() {
|
||||
op_mode = MODE_TNC;
|
||||
startRadio();
|
||||
}
|
||||
} else {
|
||||
hw_ready = false;
|
||||
debug("Error, EEPROM checksum incorrect\r\n");
|
||||
}
|
||||
} else {
|
||||
hw_ready = false;
|
||||
debug("Error, EEPROM product, model, or revision not valid\r\n");
|
||||
}
|
||||
} else {
|
||||
hw_ready = false;
|
||||
debug("Error, EEPROM info not locked\r\n");
|
||||
}
|
||||
} else {
|
||||
hw_ready = false;
|
||||
Serial.write("Error, incorrect boot vector\r\n");
|
||||
debug("Error, incorrect boot vector\r\n");
|
||||
led_indicate_boot_error();
|
||||
}
|
||||
}
|
||||
|
172
Utilities.h
172
Utilities.h
@ -13,6 +13,9 @@
|
||||
#include <poll.h>
|
||||
#include <unistd.h>
|
||||
#include <pty.h>
|
||||
#include <sys/stat.h>
|
||||
#include <sys/mman.h>
|
||||
#include <fcntl.h>
|
||||
// We need a delay()
|
||||
void delay(int ms) {
|
||||
struct timespec interval;
|
||||
@ -29,29 +32,44 @@
|
||||
static bool base_set(false);
|
||||
if (!base_set) {
|
||||
if (clock_gettime(CLOCK_MONOTONIC, &millis_base)) {
|
||||
perror("Could not get time");
|
||||
exit(1);
|
||||
}
|
||||
base_set = true;
|
||||
}
|
||||
struct timespec now;
|
||||
if (clock_gettime(CLOCK_MONOTONIC, &now)) {
|
||||
perror("Could not get time");
|
||||
exit(1);
|
||||
}
|
||||
return (now.tv_sec - millis_base.tv_sec) * 1000 + (now.tv_nsec - millis_base.tv_nsec)/(1000*1000);
|
||||
}
|
||||
|
||||
// Serial will want to poll the EEPROM a bit for help text
|
||||
bool eeprom_info_locked();
|
||||
|
||||
// We also need a Serial
|
||||
class SerialClass {
|
||||
public:
|
||||
void begin(int baud) {
|
||||
int other_end = 0;
|
||||
int status = openpty(&_fd, &other_end, NULL, NULL, NULL);
|
||||
if (status) {
|
||||
perror("could not open PTY");
|
||||
exit(1);
|
||||
// Need to be rrentrant for restart
|
||||
if (_fd <= 0) {
|
||||
int other_end = 0;
|
||||
int status = openpty(&_fd, &other_end, NULL, NULL, NULL);
|
||||
if (status) {
|
||||
perror("could not open PTY");
|
||||
exit(1);
|
||||
}
|
||||
|
||||
std::cerr << "Listening on " << ttyname(other_end) << std::endl;
|
||||
if (!eeprom_info_locked()) {
|
||||
std::cerr << "EEPROM configuration is not initialized. You will want to flash it with something like:" << std::endl;
|
||||
std::cerr << "\trnodeconf --key" << std::endl;
|
||||
std::cerr << "\trnodeconf --rom --platform " << std::hex << PLATFORM << " --product " << PRODUCT_HMBRW << " --model " << MODEL_FF << std::dec << " --hwrev 1 " << ttyname(other_end) << std::endl;
|
||||
}
|
||||
} else {
|
||||
std::cerr << "Skipping Serial reinitialization" << std::endl;
|
||||
}
|
||||
|
||||
std::cout << "Listening on " << ttyname(other_end) << std::endl;
|
||||
}
|
||||
|
||||
operator bool() {
|
||||
@ -116,6 +134,17 @@
|
||||
|
||||
#endif
|
||||
|
||||
// Log a debug message. Message should have a \r to return the cursor, if
|
||||
// needed.
|
||||
void debug(const char* message) {
|
||||
#if LIBRARY_TYPE == LIBRARY_C
|
||||
std::cerr << message << std::endl;
|
||||
#endif
|
||||
if (Serial) {
|
||||
Serial.write(message);
|
||||
}
|
||||
}
|
||||
|
||||
#if MCU_VARIANT == MCU_ESP32
|
||||
#include "soc/rtc_wdt.h"
|
||||
#define ISR_VECT IRAM_ATTR
|
||||
@ -180,13 +209,16 @@ uint8_t boot_vector = 0x00;
|
||||
void led_tx_off() { digitalWrite(pin_led_tx, LOW); }
|
||||
#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
|
||||
// No LEDs on Linux, probably. SPI only.
|
||||
void led_rx_on() { }
|
||||
void led_rx_off() { }
|
||||
void led_tx_on() { }
|
||||
void led_tx_off() { }
|
||||
#endif
|
||||
|
||||
#if LIBRARY_TYPE == LIBRARY_C
|
||||
// hard_reset needs a declaration for main
|
||||
int main(int argc, char** argv);
|
||||
#endif
|
||||
|
||||
void hard_reset(void) {
|
||||
@ -199,12 +231,17 @@ void hard_reset(void) {
|
||||
ESP.restart();
|
||||
#elif MCU_VARIANT == MCU_LINUX
|
||||
// TODO: re-exec ourselves?
|
||||
// For now just quit.
|
||||
exit(0);
|
||||
#if LIBRARY_TYPE == LIBRARY_C
|
||||
std::cerr << "Restarting" << std::endl;
|
||||
exit(main(0, NULL));
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
void led_indicate_error(int cycles) {
|
||||
#if LIBRARY_TYPE == LIBRARY_C
|
||||
std::cerr << "Indicating error" << std::endl;
|
||||
#endif
|
||||
bool forever = (cycles == 0) ? true : false;
|
||||
cycles = forever ? 1 : cycles;
|
||||
while(cycles > 0) {
|
||||
@ -221,7 +258,10 @@ void led_indicate_error(int cycles) {
|
||||
}
|
||||
|
||||
void led_indicate_boot_error() {
|
||||
while (true) {
|
||||
#if LIBRARY_TYPE == LIBRARY_C
|
||||
std::cerr << "Indicating boot error" << std::endl;
|
||||
#endif
|
||||
while (true) {
|
||||
led_tx_on();
|
||||
led_rx_off();
|
||||
delay(10);
|
||||
@ -232,6 +272,9 @@ void led_indicate_boot_error() {
|
||||
}
|
||||
|
||||
void led_indicate_warning(int cycles) {
|
||||
#if LIBRARY_TYPE == LIBRARY_C
|
||||
std::cerr << "Indicating warning" << std::endl;
|
||||
#endif
|
||||
bool forever = (cycles == 0) ? true : false;
|
||||
cycles = forever ? 1 : cycles;
|
||||
led_tx_on();
|
||||
@ -287,6 +330,9 @@ void led_indicate_warning(int cycles) {
|
||||
}
|
||||
#else
|
||||
void led_indicate_info(int cycles) {
|
||||
#if LIBRARY_TYPE == LIBRARY_C
|
||||
std::cerr << "Indicating info" << std::endl;
|
||||
#endif
|
||||
bool forever = (cycles == 0) ? true : false;
|
||||
cycles = forever ? 1 : cycles;
|
||||
while(cycles > 0) {
|
||||
@ -370,7 +416,15 @@ void led_indicate_warning(int cycles) {
|
||||
}
|
||||
#elif MCU_VARIANT == MCU_LINUX
|
||||
// No LEDs available.
|
||||
void led_indicate_standby() {}
|
||||
void led_indicate_standby() {
|
||||
#if LIBRARY_TYPE == LIBRARY_C
|
||||
static bool printed = false;
|
||||
if (!printed) {
|
||||
std::cerr << "Indicating standby" << std::endl;
|
||||
printed = true;
|
||||
}
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
#if MCU_VARIANT == MCU_1284P || MCU_VARIANT == MCU_2560
|
||||
@ -419,7 +473,15 @@ void led_indicate_warning(int cycles) {
|
||||
}
|
||||
#elif MCU_VARIANT == MCU_LINUX
|
||||
// No LEDs available.
|
||||
void led_indicate_not_ready() {}
|
||||
void led_indicate_not_ready() {
|
||||
#if LIBRARY_TYPE == LIBRARY_C
|
||||
static bool printed = false;
|
||||
if (!printed) {
|
||||
std::cerr << "Indicating not ready" << std::endl;
|
||||
printed = true;
|
||||
}
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
void escapedSerialWrite(uint8_t byte) {
|
||||
@ -682,15 +744,67 @@ void promisc_disable() {
|
||||
promisc = false;
|
||||
}
|
||||
|
||||
#if MCU_VARIANT == MCU_LINUX
|
||||
// On Linux we always use memory-mapped EEPROM
|
||||
uint8_t* eeprom_mapping = NULL;
|
||||
#endif
|
||||
#if LIBRARY_TYPE == LIBRARY_C
|
||||
// And when using the C library we set it up from a file descriptor.
|
||||
int eeprom_fd = 0;
|
||||
#endif
|
||||
|
||||
void eeprom_open(int size) {
|
||||
#if MCU_VARIANT == MCU_ESP32
|
||||
// This MCU needs EEPROIM to be begun
|
||||
EEPROM.begin(size);
|
||||
#elif MCU_VARIANT == MCU_LINUX
|
||||
// We need to use file-backed EEPROM emulation
|
||||
#if LIBRARY_TYPE == LIBRARY_C
|
||||
const char* eeprom_filename = "eeprom.dat";
|
||||
// We need to be reentrant for restarts
|
||||
if (eeprom_fd <= 0) {
|
||||
eeprom_fd = open(eeprom_filename, O_RDWR | O_CREAT, 0644);
|
||||
if (eeprom_fd <= 0) {
|
||||
perror("Could not open EEPROM file");
|
||||
exit(1);
|
||||
}
|
||||
int status = ftruncate(eeprom_fd, size);
|
||||
if (status != 0) {
|
||||
perror("Could not set size of EEPROM file");
|
||||
exit(1);
|
||||
}
|
||||
// Map EEPROM into RAM
|
||||
eeprom_mapping = (uint8_t*) mmap(NULL, size, PROT_READ | PROT_WRITE, MAP_SHARED, eeprom_fd, 0);
|
||||
if (eeprom_mapping == NULL) {
|
||||
perror("Could not map EEPROM file");
|
||||
exit(1);
|
||||
}
|
||||
std::cerr << "Mapped " << eeprom_filename << " as FD " << eeprom_fd << " to address " << (void*)eeprom_mapping << " size " << size << std::endl;
|
||||
} else {
|
||||
std::cerr << "Skipping EEPROM reinitialization" << std::endl;
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
uint8_t eeprom_read(uint8_t addr) {
|
||||
#if MCU_VARIANT == MCU_LINUX
|
||||
return 0;
|
||||
if (!eeprom_mapping) {
|
||||
throw std::runtime_error("Tried to read EEPROM before opening it!");
|
||||
}
|
||||
int mapped_address = eeprom_addr(addr);
|
||||
return eeprom_mapping[mapped_address];
|
||||
#else
|
||||
return EEPROM.read(eeprom_addr(addr));
|
||||
#endif
|
||||
}
|
||||
|
||||
bool eeprom_info_locked() {
|
||||
#if MCU_VARIANT == MCU_LINUX
|
||||
if (!eeprom_mapping) {
|
||||
return false;
|
||||
}
|
||||
#endif
|
||||
uint8_t lock_byte = eeprom_read(ADDR_INFO_LOCK);
|
||||
if (lock_byte == INFO_LOCK_BYTE) {
|
||||
return true;
|
||||
@ -707,6 +821,11 @@ void eeprom_update(int mapped_addr, uint8_t byte) {
|
||||
EEPROM.write(mapped_addr, byte);
|
||||
EEPROM.commit();
|
||||
}
|
||||
#elif MCU_VARIANT == MCU_LINUX
|
||||
if (!eeprom_mapping) {
|
||||
throw std::runtime_error("Tried to write EEPROM before opening it!");
|
||||
}
|
||||
eeprom_mapping[mapped_addr] = byte;
|
||||
#endif
|
||||
}
|
||||
|
||||
@ -760,11 +879,16 @@ bool eeprom_product_valid() {
|
||||
if (rval == PRODUCT_RNODE || rval == PRODUCT_HMBRW) {
|
||||
#elif PLATFORM == PLATFORM_ESP32
|
||||
if (rval == PRODUCT_RNODE || rval == PRODUCT_HMBRW || rval == PRODUCT_TBEAM || rval == PRODUCT_T32_20 || rval == PRODUCT_T32_21) {
|
||||
#else
|
||||
#elif PLATFORM == PLATFORM_LINUX
|
||||
if (rval == PRODUCT_HMBRW) {
|
||||
#else
|
||||
if (false) {
|
||||
#endif
|
||||
return true;
|
||||
} else {
|
||||
#if LIBRARY_TYPE == LIBRARY_C
|
||||
std::cerr << "Unacceptable platform: " << std::hex << "0x" << (int)rval << std::dec << std::endl;
|
||||
#endif
|
||||
return false;
|
||||
}
|
||||
}
|
||||
@ -790,6 +914,9 @@ bool eeprom_model_valid() {
|
||||
#endif
|
||||
return true;
|
||||
} else {
|
||||
#if LIBRARY_TYPE == LIBRARY_C
|
||||
std::cerr << "Unacceptable model: " << std::hex << "0x" << (int)model << std::dec << std::endl;
|
||||
#endif
|
||||
return false;
|
||||
}
|
||||
}
|
||||
@ -799,6 +926,9 @@ bool eeprom_hwrev_valid() {
|
||||
if (hwrev != 0x00 && hwrev != 0xFF) {
|
||||
return true;
|
||||
} else {
|
||||
#if LIBRARY_TYPE == LIBRARY_C
|
||||
std::cerr << "Unacceptable revision: " << std::hex << "0x" << (int)hwrev << std::dec << std::endl;
|
||||
#endif
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user