Merge pull request from vfurman-gh/master

Port to isp4520-based board
This commit is contained in:
Kevin Hester 2021-03-20 09:01:06 +08:00 committed by GitHub
commit 5cc3ff16a3
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
19 changed files with 617 additions and 220 deletions

48
boards/lora_isp4520.json Normal file
View File

@ -0,0 +1,48 @@
{
"build": {
"arduino": {
"ldscript": "nrf52832_s132_v6.ld"
},
"core": "nRF5",
"cpu": "cortex-m4",
"extra_flags": "-DNRF52832_XXAA -DNRF52",
"f_cpu": "64000000L",
"mcu": "nrf52832",
"variant": "lora_isp4520",
"bsp": {
"name": "adafruit"
},
"softdevice": {
"sd_flags": "-DS132",
"sd_name": "s132",
"sd_version": "6.1.1",
"sd_fwid": "0x00B7"
}
},
"connectivity": [
"bluetooth"
],
"debug": {
"jlink_device": "nRF52832_xxAA",
"svd_path": "nrf52.svd"
},
"frameworks": [
"arduino"
],
"name": "lora ISP4520",
"upload": {
"maximum_ram_size": 65536,
"maximum_size": 524288,
"require_upload_port": true,
"speed": 115200,
"protocol": "nrfutil",
"protocols": [
"jlink",
"nrfjprog",
"nrfutil",
"stlink"
]
},
"url": "",
"vendor": "PsiSoft"
}

View File

@ -39,7 +39,7 @@ extra_scripts = bin/platformio-custom.py
; FIXME: fix lib/BluetoothOTA dependency back on src/ so we can remove -Isrc
build_flags = -Wno-missing-field-initializers
-Wno-format
-Isrc -Isrc/mesh -Isrc/gps -Ilib/nanopb/include -Wl,-Map,.pio/build/output.map
-Isrc -Isrc/mesh -Isrc/gps -Ilib/nanopb/include -Isrc/buzz -Wl,-Map,.pio/build/output.map
-DHW_VERSION_${sysenv.COUNTRY}
-DHW_VERSION=${sysenv.HW_VERSION}
-DUSE_THREAD_NAMES
@ -232,6 +232,24 @@ debug_init_break =
;debug_init_break = tbreak loop
;debug_init_break = tbreak Reset_Handler
[env:lora_isp4520]
extends = nrf52_base
board = lora_isp4520
# add our variants files to the include and src paths
build_flags = ${nrf52_base.build_flags} -Ivariants/lora_isp4520
# No screen and GPS on the board. We still need RTC.cpp for the RTC clock.
src_filter = ${nrf52_base.src_filter} +<../variants/lora_isp4520> -<graphics> -<gps> +<gps/GPS.cpp> +<gps/RTC.cpp>
lib_ignore = ${nrf52_base.lib_ignore}
ESP8266_SSD1306
SparkFun Ublox Arduino Library
AXP202X_Library
TinyGPSPlus
upload_protocol = jlink
monitor_port = /dev/ttyUSB0
; The NRF52840-dk development board
; Note: By default no lora device is created for this build - it uses a simulated interface
[env:nrf52840dk]

View File

@ -5,12 +5,35 @@
#include "sleep.h"
#include "utils.h"
#ifdef TBEAM_V10
// FIXME. nasty hack cleanup how we load axp192
#undef AXP192_SLAVE_ADDRESS
#include "axp20x.h"
#ifdef TBEAM_V10
AXP20X_Class axp;
#else
// Copy of the base class defined in axp20x.h.
// I'd rather not inlude axp20x.h as it brings Wire dependency.
class HasBatteryLevel {
public:
/**
* Battery state of charge, from 0 to 100 or -1 for unknown
*/
virtual int getBattPercentage() { return -1; }
/**
* The raw voltage of the battery or NAN if unknown
*/
virtual float getBattVoltage() { return NAN; }
/**
* return true if there is a battery installed in this unit
*/
virtual bool isBatteryConnect() { return false; }
virtual bool isVBUSPlug() { return false; }
virtual bool isChargeing() { return false; }
};
#endif
bool pmu_irq = false;
@ -51,7 +74,7 @@ class AnalogBatteryLevel : public HasBatteryLevel
*/
virtual int getBattPercentage()
{
float v = getBattVoltage() / 1000;
float v = getBattVoltage();
if (v < noBatVolt)
return -1; // If voltage is super low assume no battery installed
@ -67,13 +90,26 @@ class AnalogBatteryLevel : public HasBatteryLevel
*/
virtual float getBattVoltage()
{
// Tested ttgo eink nrf52 board and the reported value is perfect
// DEBUG_MSG("raw val %u", raw);
return
#ifndef ADC_MULTIPLIER
#define ADC_MULTIPLIER 2.0
#endif
#ifdef BATTERY_PIN
1000.0 * 2.0 * (AREF_VOLTAGE / 1024.0) * analogRead(BATTERY_PIN);
// Do not call analogRead() often.
const uint32_t min_read_interval = 5000;
if (millis() - last_read_time_ms > min_read_interval) {
last_read_time_ms = millis();
uint32_t raw = analogRead(BATTERY_PIN);
float scaled = 1000.0 * ADC_MULTIPLIER * (AREF_VOLTAGE / 1024.0) * raw;
// DEBUG_MSG("raw val=%u scaled=%u\n", raw, (uint32_t)(scaled));
last_read_value = scaled;
return scaled;
} else {
return last_read_value;
}
#else
NAN;
return NAN;
#endif
}
@ -93,7 +129,9 @@ class AnalogBatteryLevel : public HasBatteryLevel
private:
/// If we see a battery voltage higher than physics allows - assume charger is pumping
/// in power
const float fullVolt = 4.2, emptyVolt = 3.27, chargingVolt = 4.3, noBatVolt = 2.1;
const float fullVolt = 4200, emptyVolt = 3270, chargingVolt = 4210, noBatVolt = 2100;
float last_read_value = 0.0;
uint32_t last_read_time_ms = 0;
} analogLevel;
Power::Power() : OSThread("Power") {}
@ -140,6 +178,8 @@ void Power::shutdown()
#ifdef TBEAM_V10
DEBUG_MSG("Shutting down\n");
axp.shutdown();
#elif NRF52_SERIES
doDeepSleep(DELAY_FOREVER);
#endif
}

View File

@ -97,7 +97,7 @@ static void lsIdle()
static void lsExit()
{
// setGPSPower(true); // restore GPS power
gps->forceWake(true);
if (gps) gps->forceWake(true);
}
static void nbEnter()

View File

@ -4,49 +4,49 @@
#include <assert.h>
#include <sys/time.h>
#include <time.h>
#include "RTC.h"
/**
* A printer that doesn't go anywhere
*/
NoopPrint noopPrint;
void RedirectablePrint::setDestination(Print *_dest)
{
assert(_dest);
dest = _dest;
void RedirectablePrint::setDestination(Print *_dest) {
assert(_dest);
dest = _dest;
}
size_t RedirectablePrint::write(uint8_t c)
{
// Always send the characters to our segger JTAG debugger
size_t RedirectablePrint::write(uint8_t c) {
// Always send the characters to our segger JTAG debugger
#ifdef SEGGER_STDOUT_CH
SEGGER_RTT_PutChar(SEGGER_STDOUT_CH, c);
#endif
dest->write(c);
return 1; // We always claim one was written, rather than trusting what the serial port said (which could be zero)
dest->write(c);
return 1; // We always claim one was written, rather than trusting what the
// serial port said (which could be zero)
}
size_t RedirectablePrint::vprintf(const char *format, va_list arg)
{
va_list copy;
va_list copy;
va_copy(copy, arg);
int len = vsnprintf(printBuf, printBufLen, format, copy);
va_end(copy);
if (len < 0) {
va_end(arg);
return 0;
};
if (len >= printBufLen) {
delete[] printBuf;
printBufLen *= 2;
printBuf = new char[printBufLen];
len = vsnprintf(printBuf, printBufLen, format, arg);
}
va_copy(copy, arg);
int len = vsnprintf(printBuf, printBufLen, format, copy);
va_end(copy);
if (len < 0) {
va_end(arg);
return 0;
};
if (len >= (int)printBufLen) {
delete[] printBuf;
printBufLen *= 2;
printBuf = new char[printBufLen];
len = vsnprintf(printBuf, printBufLen, format, arg);
}
len = Print::write(printBuf, len);
return len;
len = Print::write(printBuf, len);
return len;
}
#define SEC_PER_DAY 86400
@ -68,9 +68,9 @@ size_t RedirectablePrint::logDebug(const char *format, ...)
// If we are the first message on a report, include the header
if (!isContinuationMessage) {
struct timeval tv;
if (!gettimeofday(&tv, NULL)) {
long hms = tv.tv_sec % SEC_PER_DAY;
uint32_t rtc_sec = getValidTime(RTCQuality::RTCQualityFromNet);
if (rtc_sec > 0) {
long hms =rtc_sec % SEC_PER_DAY;
// hms += tz.tz_dsttime * SEC_PER_HOUR;
// hms -= tz.tz_minuteswest * SEC_PER_MIN;
// mod `hms` to ensure in positive range of [0...SEC_PER_DAY)
@ -102,5 +102,5 @@ size_t RedirectablePrint::logDebug(const char *format, ...)
inDebugPrint = false;
}
return r;
return r;
}

66
src/buzz/buzz.cpp Normal file
View File

@ -0,0 +1,66 @@
#include "buzz.h"
#include "configuration.h"
#ifdef NRF52_SERIES
#include "variant.h"
#endif
#ifndef PIN_BUZZER
// Noop methods for boards w/o buzzer
void playBeep(){};
void playStartMelody(){};
void playShutdownMelody(){};
#else
#include "Tone.h"
extern "C" void delay(uint32_t dwMs);
struct ToneDuration {
int frequency_khz;
int duration_ms;
};
// Some common frequencies.
#define NOTE_C3 131
#define NOTE_CS3 139
#define NOTE_D3 147
#define NOTE_DS3 156
#define NOTE_E3 165
#define NOTE_F3 175
#define NOTE_FS3 185
#define NOTE_G3 196
#define NOTE_GS3 208
#define NOTE_A3 220
#define NOTE_AS3 233
#define NOTE_B3 247
const int DURATION_1_8 = 125; // 1/8 note
const int DURATION_1_4 = 250; // 1/4 note
void playTones(const ToneDuration *tone_durations, int size) {
for (int i = 0; i < size; i++) {
const auto &tone_duration = tone_durations[i];
tone(PIN_BUZZER, tone_duration.frequency_khz, tone_duration.duration_ms);
// to distinguish the notes, set a minimum time between them.
delay(1.3 * tone_duration.duration_ms);
}
}
void playBeep() { tone(PIN_BUZZER, NOTE_B3, DURATION_1_4); }
void playStartMelody() {
ToneDuration melody[] = {{NOTE_B3, DURATION_1_4},
{NOTE_B3, DURATION_1_8},
{NOTE_B3, DURATION_1_8}};
playTones(melody, sizeof(melody) / sizeof(ToneDuration));
}
void playShutdownMelody() {
ToneDuration melody[] = {{NOTE_B3, DURATION_1_4},
{NOTE_G3, DURATION_1_8},
{NOTE_D3, DURATION_1_8}};
playTones(melody, sizeof(melody) / sizeof(ToneDuration));
}
#endif

5
src/buzz/buzz.h Normal file
View File

@ -0,0 +1,5 @@
#pragma once
void playBeep();
void playStartMelody();
void playShutdownMelody();

View File

@ -459,6 +459,8 @@ along with this program. If not, see <http://www.gnu.org/licenses/>.
#define DEBUG_PORT console // Serial debug port
// What platforms should use SEGGER?
#ifdef NRF52_SERIES

View File

@ -308,3 +308,49 @@ int GPS::prepareDeepSleep(void *unused)
return 0;
}
#ifdef GPS_TX_PIN
#include "UBloxGPS.h"
#endif
#ifdef HAS_AIR530_GPS
#include "Air530GPS.h"
#elif !defined(NO_GPS)
#include "NMEAGPS.h"
#endif
GPS* createGps() {
#ifdef NO_GPS
return nullptr;
#else
// If we don't have bidirectional comms, we can't even try talking to UBLOX
#ifdef GPS_TX_PIN
// Init GPS - first try ublox
UBloxGPS *ublox = new UBloxGPS();
if (!ublox->setup()) {
DEBUG_MSG("ERROR: No UBLOX GPS found\n");
delete ublox;
ublox = NULL;
} else {
return ublox;
}
#endif
if (GPS::_serial_gps) {
// Some boards might have only the TX line from the GPS connected, in that case, we can't configure it at all. Just
// assume NMEA at 9600 baud.
DEBUG_MSG("Hoping that NMEA might work\n");
#ifdef HAS_AIR530_GPS
GPS* new_gps = new Air530GPS();
#else
GPS* new_gps = new NMEAGPS();
#endif
new_gps->setup();
return new_gps;
}
return nullptr;
#endif
}

View File

@ -71,6 +71,9 @@ class GPS : private concurrency::OSThread
* */
void forceWake(bool on);
// Some GPS modules (ublock) require factory reset
virtual bool factoryReset() { return true; }
protected:
/// Do gps chipset specific init, return true for success
virtual bool setupGPS();
@ -145,4 +148,8 @@ class GPS : private concurrency::OSThread
virtual int32_t runOnce();
};
// Creates an instance of the GPS class.
// Returns the new instance or null if the GPS is not present.
GPS* createGps();
extern GPS *gps;

View File

@ -42,19 +42,20 @@ bool perhapsSetRTC(RTCQuality q, const struct timeval *tv)
} else if(q == RTCQualityGPS && (now - lastSetMsec) > (12 * 60 * 60 * 1000L)) {
// Every 12 hrs we will slam in a new GPS time, to correct for local RTC clock drift
shouldSet = true;
DEBUG_MSG("Reapplying GPS time to correct clock drift %ld secs\n", tv->tv_sec);
DEBUG_MSG("Reapplying external time to correct clock drift %ld secs\n", tv->tv_sec);
}
else
shouldSet = false;
if (shouldSet) {
lastSetMsec = now;
lastSetMsec = now;
#ifndef NO_ESP32
settimeofday(tv, NULL);
#else
DEBUG_MSG("ERROR TIME SETTING NOT IMPLEMENTED!\n");
#endif
readFromRTC();
#else
timeStartMsec = now;
zeroOffsetSecs = tv->tv_sec;
#endif
return true;
} else {
return false;

View File

@ -1,5 +1,23 @@
#pragma once
#ifdef NO_SCREEN
namespace graphics
{
// Noop class for boards without screen.
class Screen
{
public:
Screen(char){}
void onPress() {}
void setup() {}
void setOn(bool) {}
void print(const char*){}
void adjustBrightness(){}
void doDeepSleep() {}
};
}
#else
#include <cstring>
#include <OLEDDisplayUi.h>
@ -278,3 +296,4 @@ class Screen : public concurrency::OSThread
};
} // namespace graphics
#endif

View File

@ -1,11 +1,11 @@
#include "Air530GPS.h"
#include "GPS.h"
#include "MeshRadio.h"
#include "MeshService.h"
#include "NodeDB.h"
#include "PowerFSM.h"
#include "UBloxGPS.h"
#include "airtime.h"
#include "buzz.h"
#include "configuration.h"
#include "error.h"
#include "power.h"
@ -67,7 +67,7 @@ Router *router = NULL; // Users of router don't care what sort of subclass imple
// -----------------------------------------------------------------------------
// Application
// -----------------------------------------------------------------------------
#if WIRE_INTERFACES_COUNT > 0
void scanI2Cdevice(void)
{
byte err, addr;
@ -104,6 +104,9 @@ void scanI2Cdevice(void)
else
DEBUG_MSG("done\n");
}
#else
void scanI2Cdevice(void) {}
#endif
const char *getDeviceName()
{
@ -173,7 +176,7 @@ class ButtonThread : public OSThread
#ifdef BUTTON_PIN_ALT
OneButton userButtonAlt;
#endif
static bool shutdown_on_long_stop;
public:
static uint32_t longPressTime;
@ -239,13 +242,23 @@ class ButtonThread : public OSThread
// DEBUG_MSG("Long press!\n");
screen->adjustBrightness();
// If user button is held down for 10 seconds, shutdown the device.
if (millis() - longPressTime > 10 * 1000) {
// If user button is held down for 5 seconds, shutdown the device.
if (millis() - longPressTime > 5 * 1000) {
#ifdef TBEAM_V10
if (axp192_found == true) {
setLed(false);
power->shutdown();
}
#elif NRF52_SERIES
// Do actual shutdown when button released, otherwise the button release
// may wake the board immediatedly.
if (!shutdown_on_long_stop) {
DEBUG_MSG("Shutdown from long press");
playBeep();
ledOff(PIN_LED1);
ledOff(PIN_LED2);
shutdown_on_long_stop = true;
}
#endif
} else {
// DEBUG_MSG("Long press %u\n", (millis() - longPressTime));
@ -269,9 +282,15 @@ class ButtonThread : public OSThread
{
DEBUG_MSG("Long press stop!\n");
longPressTime = 0;
if (shutdown_on_long_stop) {
playShutdownMelody();
power->shutdown();
}
}
};
bool ButtonThread::shutdown_on_long_stop = false;
static Periodic *ledPeriodic;
static OSThread *powerFSMthread, *buttonThread;
uint32_t ButtonThread::longPressTime = 0;
@ -345,7 +364,7 @@ void setup()
#ifdef I2C_SDA
Wire.begin(I2C_SDA, I2C_SCL);
#else
#elif WIRE_INTERFACES_COUNT > 0
Wire.begin();
#endif
@ -382,7 +401,7 @@ void setup()
#ifdef NRF52_SERIES
nrf52Setup();
#endif
playStartMelody();
// We do this as early as possible because this loads preferences from flash
// but we need to do this after main cpu iniot (esp32setup), because we need the random seed set
nodeDB.init();
@ -420,34 +439,7 @@ void setup()
pinMode(BATTERY_EN_PIN, OUTPUT);
digitalWrite(BATTERY_EN_PIN, LOW);
#endif
// If we don't have bidirectional comms, we can't even try talking to UBLOX
UBloxGPS *ublox = NULL;
#ifdef GPS_TX_PIN
// Init GPS - first try ublox
ublox = new UBloxGPS();
gps = ublox;
if (!gps->setup()) {
DEBUG_MSG("ERROR: No UBLOX GPS found\n");
delete ublox;
gps = ublox = NULL;
}
#endif
if (!gps && GPS::_serial_gps) {
// Some boards might have only the TX line from the GPS connected, in that case, we can't configure it at all. Just
// assume NMEA at 9600 baud.
// dumb NMEA access only work for serial GPSes)
DEBUG_MSG("Hoping that NMEA might work\n");
#ifdef HAS_AIR530_GPS
gps = new Air530GPS();
#else
gps = new NMEAGPS();
#endif
gps->setup();
}
gps = createGps();
if (gps)
gpsStatus->observe(&gps->newStatus);
@ -481,8 +473,8 @@ void setup()
// We have now loaded our saved preferences from flash
// ONCE we will factory reset the GPS for bug #327
if (ublox && !devicestate.did_gps_reset) {
if (ublox->factoryReset()) { // If we don't succeed try again next time
if (gps && !devicestate.did_gps_reset) {
if (gps->factoryReset()) { // If we don't succeed try again next time
devicestate.did_gps_reset = true;
nodeDB.saveToDisk();
}

View File

@ -1,9 +1,13 @@
#pragma once
#include "mesh/MeshTypes.h"
#include <vector>
#ifndef NO_SCREEN
#include <OLEDDisplay.h>
#include <OLEDDisplayUi.h>
#include <vector>
#endif
/** A baseclass for any mesh "plugin".
*
* A plugin allows you to add new features to meshtastic device code, without needing to know messaging details.
@ -31,9 +35,9 @@ class MeshPlugin
static void callPlugins(const MeshPacket &mp);
static std::vector<MeshPlugin *> GetMeshPluginsWithUIFrames();
#ifndef NO_SCREEN
virtual void drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y) { return; }
#endif
protected:
const char *name;

View File

@ -34,11 +34,11 @@ bool SX1262Interface::init()
pinMode(SX1262_TXEN, OUTPUT);
#endif
#ifndef SX1262_E22
#if !defined(SX1262_E22) && !defined(SX1262_USE_DIO3_FOR_TCXO)
float tcxoVoltage = 0; // None - we use an XTAL
#else
float tcxoVoltage =
1.8; // E22 uses DIO3 to power tcxo per https://github.com/jgromes/RadioLib/issues/12#issuecomment-520695575
// Use DIO3 to power tcxo per https://github.com/jgromes/RadioLib/issues/12#issuecomment-520695575
float tcxoVoltage = 1.8;
#endif
bool useRegulatorLDO = false; // Seems to depend on the connection to pin 9/DCC_SW - if an inductor DCDC?

View File

@ -3,8 +3,8 @@
#include "configuration.h"
#include "main.h"
#include <bluefruit.h>
#include "mesh/mesh-pb-constants.h"
#include "mesh/PhoneAPI.h"
static BLEService meshBleService = BLEService(BLEUuid(MESH_SERVICE_UUID_16));
static BLECharacteristic fromNum = BLECharacteristic(BLEUuid(FROMNUM_UUID_16));
@ -213,6 +213,7 @@ void NRF52Bluetooth::setup()
{
// Initialise the Bluefruit module
DEBUG_MSG("Initialise the Bluefruit nRF52 module\n");
Bluefruit.autoConnLed(false);
Bluefruit.begin();
// Set the advertised device name (keep it short!)

View File

@ -1,7 +1,3 @@
#include "NRF52Bluetooth.h"
#include "configuration.h"
#include "error.h"
#include "graphics/TFTDisplay.h"
#include <SPI.h>
#include <Wire.h>
#include <assert.h>
@ -9,179 +5,182 @@
#include <memory.h>
#include <stdio.h>
#ifdef NRF52840_XXAA
// #include <nrf52840.h>
#include "NRF52Bluetooth.h"
#include "configuration.h"
#include "error.h"
#ifdef BQ25703A_ADDR
#include "BQ25713.h"
#endif
// #define USE_SOFTDEVICE
static inline void debugger_break(void)
{
__asm volatile("bkpt #0x01\n\t"
"mov pc, lr\n\t");
static inline void debugger_break(void) {
__asm volatile(
"bkpt #0x01\n\t"
"mov pc, lr\n\t");
}
// handle standard gcc assert failures
void __attribute__((noreturn)) __assert_func(const char *file, int line, const char *func, const char *failedexpr)
{
DEBUG_MSG("assert failed %s: %d, %s, test=%s\n", file, line, func, failedexpr);
// debugger_break(); FIXME doesn't work, possibly not for segger
while (1)
; // FIXME, reboot!
void __attribute__((noreturn))
__assert_func(const char *file, int line, const char *func,
const char *failedexpr) {
DEBUG_MSG("assert failed %s: %d, %s, test=%s\n", file, line, func,
failedexpr);
// debugger_break(); FIXME doesn't work, possibly not for segger
while (1)
; // FIXME, reboot!
}
void getMacAddr(uint8_t *dmac)
{
ble_gap_addr_t addr;
#ifdef USE_SOFTDEVICE
uint32_t res = sd_ble_gap_addr_get(&addr);
assert(res == NRF_SUCCESS);
void getMacAddr(uint8_t *dmac) {
ble_gap_addr_t addr;
if (sd_ble_gap_addr_get(&addr) == NRF_SUCCESS) {
memcpy(dmac, addr.addr, 6);
#else
} else {
const uint8_t *src = (const uint8_t *)NRF_FICR->DEVICEADDR;
dmac[5] = src[0];
dmac[4] = src[1];
dmac[3] = src[2];
dmac[2] = src[3];
dmac[1] = src[4];
dmac[0] = src[5] | 0xc0; // MSB high two bits get set elsewhere in the bluetooth stack
#endif
dmac[0] = src[5] |
0xc0; // MSB high two bits get set elsewhere in the bluetooth stack
}
}
NRF52Bluetooth *nrf52Bluetooth;
static bool bleOn = false;
static const bool useSoftDevice = false; // Set to false for easier debugging
static const bool useSoftDevice = true; // Set to false for easier debugging
void setBluetoothEnable(bool on)
{
if (on != bleOn) {
if (on) {
if (!nrf52Bluetooth) {
if (!useSoftDevice)
DEBUG_MSG("DISABLING NRF52 BLUETOOTH WHILE DEBUGGING\n");
else {
nrf52Bluetooth = new NRF52Bluetooth();
nrf52Bluetooth->setup();
}
}
} else {
if (nrf52Bluetooth)
nrf52Bluetooth->shutdown();
void setBluetoothEnable(bool on) {
if (on != bleOn) {
if (on) {
if (!nrf52Bluetooth) {
if (!useSoftDevice)
DEBUG_MSG("DISABLING NRF52 BLUETOOTH WHILE DEBUGGING\n");
else {
nrf52Bluetooth = new NRF52Bluetooth();
nrf52Bluetooth->setup();
}
bleOn = on;
}
} else {
if (nrf52Bluetooth) nrf52Bluetooth->shutdown();
}
bleOn = on;
}
}
/**
* Override printf to use the SEGGER output library
*/
int printf(const char *fmt, ...)
{
va_list args;
va_start(args, fmt);
auto res = SEGGER_RTT_vprintf(0, fmt, &args);
va_end(args);
return res;
int printf(const char *fmt, ...) {
va_list args;
va_start(args, fmt);
auto res = SEGGER_RTT_vprintf(0, fmt, &args);
va_end(args);
return res;
}
#include "BQ25713.h"
void initBrownout() {
auto vccthresh = POWER_POFCON_THRESHOLD_V28;
void initBrownout()
{
auto vccthresh = POWER_POFCON_THRESHOLD_V28;
if (useSoftDevice) {
auto err_code = sd_power_pof_enable(POWER_POFCON_POF_Enabled);
assert(err_code == NRF_SUCCESS);
err_code = sd_power_pof_threshold_set(vccthresh);
assert(err_code == NRF_SUCCESS);
} else {
uint32_t pof_flags = POWER_POFCON_POF_Enabled | (vccthresh << POWER_POFCON_THRESHOLD_Pos);
#ifdef POWER_POFCON_THRESHOLDVDDH_Msk
auto vcchthresh = POWER_POFCON_THRESHOLDVDDH_V27;
if (useSoftDevice) {
auto err_code = sd_power_pof_enable(POWER_POFCON_POF_Enabled);
assert(err_code == NRF_SUCCESS);
err_code = sd_power_pof_threshold_set(vccthresh);
assert(err_code == NRF_SUCCESS);
}
else {
NRF_POWER->POFCON = POWER_POFCON_POF_Msk | (vccthresh << POWER_POFCON_THRESHOLD_Pos) | (vcchthresh << POWER_POFCON_THRESHOLDVDDH_Pos);
}
pof_flags |= (vcchthresh << POWER_POFCON_THRESHOLDVDDH_Pos);
#endif
NRF_POWER->POFCON = pof_flags;
}
}
void checkSDEvents()
{
if (useSoftDevice) {
uint32_t evt;
while (NRF_ERROR_NOT_FOUND == sd_evt_get(&evt)) {
switch (evt) {
case NRF_EVT_POWER_FAILURE_WARNING:
recordCriticalError(CriticalErrorCode_Brownout);
break;
void checkSDEvents() {
if (useSoftDevice) {
uint32_t evt;
while (NRF_SUCCESS == sd_evt_get(&evt)) {
switch (evt) {
case NRF_EVT_POWER_FAILURE_WARNING:
recordCriticalError(CriticalErrorCode_Brownout);
break;
default:
DEBUG_MSG("Unexpected SDevt %d\n", evt);
break;
}
}
} else {
if(NRF_POWER->EVENTS_POFWARN)
recordCriticalError(CriticalErrorCode_Brownout);
default:
DEBUG_MSG("Unexpected SDevt %d\n", evt);
break;
}
}
} else {
if (NRF_POWER->EVENTS_POFWARN)
recordCriticalError(CriticalErrorCode_Brownout);
}
}
void nrf52Loop()
{
checkSDEvents();
}
void nrf52Loop() { checkSDEvents(); }
void nrf52Setup()
{
void nrf52Setup() {
auto why = NRF_POWER->RESETREAS;
// per
// https://infocenter.nordicsemi.com/index.jsp?topic=%2Fcom.nordic.infocenter.nrf52832.ps.v1.1%2Fpower.html
DEBUG_MSG("Reset reason: 0x%x\n", why);
auto why = NRF_POWER->RESETREAS;
// per https://infocenter.nordicsemi.com/index.jsp?topic=%2Fcom.nordic.infocenter.nrf52832.ps.v1.1%2Fpower.html
DEBUG_MSG("Reset reason: 0x%x\n", why);
// Per https://devzone.nordicsemi.com/nordic/nordic-blog/b/blog/posts/monitor-mode-debugging-with-j-link-and-gdbeclipse
// This is the recommended setting for Monitor Mode Debugging
NVIC_SetPriority(DebugMonitor_IRQn, 6UL);
// Per
// https://devzone.nordicsemi.com/nordic/nordic-blog/b/blog/posts/monitor-mode-debugging-with-j-link-and-gdbeclipse
// This is the recommended setting for Monitor Mode Debugging
NVIC_SetPriority(DebugMonitor_IRQn, 6UL);
#ifdef BQ25703A_ADDR
auto *bq = new BQ25713();
if (!bq->setup())
DEBUG_MSG("ERROR! Charge controller init failed\n");
auto *bq = new BQ25713();
if (!bq->setup()) DEBUG_MSG("ERROR! Charge controller init failed\n");
#endif
// Init random seed
// FIXME - use this to get random numbers
// #include "nrf_rng.h"
// uint32_t r;
// ble_controller_rand_vector_get_blocking(&r, sizeof(r));
// randomSeed(r);
DEBUG_MSG("FIXME, call randomSeed\n");
// ::printf("TESTING PRINTF\n");
// Init random seed
// FIXME - use this to get random numbers
// #include "nrf_rng.h"
// uint32_t r;
// ble_controller_rand_vector_get_blocking(&r, sizeof(r));
// randomSeed(r);
DEBUG_MSG("FIXME, call randomSeed\n");
// ::printf("TESTING PRINTF\n");
initBrownout();
initBrownout();
}
void cpuDeepSleep(uint64_t msecToWake)
{
// FIXME, configure RTC or button press to wake us
// FIXME, power down SPI, I2C, RAMs
Wire.end();
SPI.end();
Serial.end();
Serial1.end();
void cpuDeepSleep(uint64_t msecToWake) {
// FIXME, configure RTC or button press to wake us
// FIXME, power down SPI, I2C, RAMs
#if WIRE_INTERFACES_COUNT > 0
Wire.end();
#endif
SPI.end();
// This may cause crashes as debug messages continue to flow.
Serial.end();
// FIXME, use system off mode with ram retention for key state?
// FIXME, use non-init RAM per
// https://devzone.nordicsemi.com/f/nordic-q-a/48919/ram-retention-settings-with-softdevice-enabled
#ifdef PIN_SERIAL_RX1
Serial1.end();
#endif
setBluetoothEnable(false);
// FIXME, use system off mode with ram retention for key state?
// FIXME, use non-init RAM per
// https://devzone.nordicsemi.com/f/nordic-q-a/48919/ram-retention-settings-with-softdevice-enabled
auto ok = sd_power_system_off();
if (ok != NRF_SUCCESS) {
DEBUG_MSG("FIXME: Ignoring soft device (EasyDMA pending?) and forcing system-off!\n");
NRF_POWER->SYSTEMOFF = 1;
}
auto ok = sd_power_system_off();
if (ok != NRF_SUCCESS) {
DEBUG_MSG(
"FIXME: Ignoring soft device (EasyDMA pending?) and forcing "
"system-off!\n");
NRF_POWER->SYSTEMOFF = 1;
}
// The following code should not be run, because we are off
while (1) {
delay(5000);
DEBUG_MSG(".");
}
// The following code should not be run, because we are off
while (1) {
delay(5000);
DEBUG_MSG(".");
}
}

View File

@ -0,0 +1,52 @@
/*
Copyright (c) 2014-2015 Arduino LLC. All right reserved.
Copyright (c) 2016 Sandeep Mistry All right reserved.
Copyright (c) 2018, Adafruit Industries (adafruit.com)
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
See the GNU Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
#include "variant.h"
#include "nrf.h"
#include "wiring_constants.h"
#include "wiring_digital.h"
const uint32_t g_ADigitalPinMap[] = {
25, // D0 SPI_MISO
24, // D1 SPI_NSS
23, // D2 SPI_SCK
4, // D3 VBAT
11, // D4 DIO1
27, // D5 BUSY
19, // D6 NRESET
12, // D7 BUTTON2
22, // D8 BUTTON3
26, // D9 SPI_MOSI
31, // D10 UART_RX
2, // D11 UART_TX
10, // D12 LED1 GREEN
17, // D13 LED2 RED
9, // D14 BUZZER
7, // D15 BUTTON1
};
#include <initializer_list>
void initVariant()
{
for (int i : {PIN_LED1, PIN_LED2}) {
pinMode(i, OUTPUT);
ledOff(i);
}
}

View File

@ -0,0 +1,97 @@
/*
Copyright (c) 2014-2015 Arduino LLC. All right reserved.
Copyright (c) 2016 Sandeep Mistry All right reserved.
Copyright (c) 2018, Adafruit Industries (adafruit.com)
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
See the GNU Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
#ifndef _VARIANT_LORA_ISP4520_
#define _VARIANT_LORA_ISP4520_
#define HW_VERSION_US 1
#undef HW_VERSION
#define HW_VERSION "1.0"
#define USE_SEGGER
/*----------------------------------------------------------------------------
* Headers
*----------------------------------------------------------------------------*/
#include "WVariant.h"
#define USE_LFXO
//#define USE_SEGGER
// Number of pins defined in PinDescription array
#define PINS_COUNT (16)
#define NUM_DIGITAL_PINS (16)
#define NUM_ANALOG_INPUTS (1)
#define NUM_ANALOG_OUTPUTS (1)
/*
* SPI Interfaces
*/
#define SPI_INTERFACES_COUNT 1
// These are in arduino pin numbers,
// translation in g_ADigitalPinMap in variants.cpp
#define PIN_SPI_MISO (0)
#define PIN_SPI_MOSI (9)
#define PIN_SPI_SCK (2)
/*
* Wire Interfaces (I2C)
*/
#define WIRE_INTERFACES_COUNT 0
// GPIOs the SX1262 is connected
#define SX1262_CS 1 // aka SPI_NSS
#define SX1262_DIO1 (4)
#define SX1262_BUSY (5)
#define SX1262_RESET (6)
/*
* Serial interfaces
*/
#define PIN_SERIAL_RX (10)
#define PIN_SERIAL_TX (11)
// LEDs
#define PIN_LED1 (12)
#define PIN_LED2 (13)
#define PIN_BUZZER (14)
#define LED_BUILTIN PIN_LED1
#define LED_CONN PIN_LED2
#define LED_RED PIN_LED1
#define LED_BLUE PIN_LED2
#define LED_STATE_ON 1 // State when LED is litted
/*
* Buttons
*/
#define PIN_BUTTON1 (15)
#define PIN_BUTTON2 (7)
#define PIN_BUTTON3 (8)
// ADC pin and voltage divider
#define BATTERY_PIN 3
#define ADC_MULTIPLIER 1.436
#define SX1262_USE_DIO3_FOR_TCXO
#define NO_GPS
#define NO_SCREEN
#endif