Merge branch 'master' into raspi-portduino

This commit is contained in:
Ben Meadors 2023-05-18 06:47:56 -05:00 committed by GitHub
commit 9bee35118f
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
57 changed files with 289 additions and 118 deletions

View File

@ -1,7 +1,7 @@
; Common settings for ESP targes, mixin with extends = esp32_base
[esp32_base]
extends = arduino_base
platform = platformio/espressif32@^6.1.0
platform = platformio/espressif32@^6.2.0
build_src_filter =
${arduino_base.build_src_filter} -<platform/nrf52/> -<platform/stm32wl> -<platform/rp2040> -<mesh/eth/>

View File

@ -1,6 +1,6 @@
[nrf52_base]
; Instead of the standard nordicnrf52 platform, we use our fork which has our added variant files
platform = platformio/nordicnrf52@^9.5.0
platform = platformio/nordicnrf52@^9.6.0
extends = arduino_base
build_type = debug ; I'm debugging with ICE a lot now

View File

@ -17,4 +17,4 @@ lib_deps =
https://github.com/kokke/tiny-AES-c.git#f06ac37fc31dfdaca2e0d9bec83f90d5663c319b
lib_ignore =
mathertel/OneButton@^2.0.3
https://github.com/mathertel/OneButton#2.1.0

View File

@ -7,12 +7,12 @@ default_envs = tbeam
;default_envs = tbeam-s3-core
;default_envs = tbeam0.7
;default_envs = heltec-v1
;default_envs = heltec-v2.0
;default_envs = heltec-v2.1
;default_envs = heltec-v2_0
;default_envs = heltec-v2_1
;default_envs = tlora-v1
;default_envs = tlora_v1_3
;default_envs = tlora-v2
;default_envs = tlora-v2-1-1.6
;default_envs = tlora-v2-1-1_6
;default_envs = tlora-t3s3-v1
;default_envs = lora-relay-v1 # nrf board
;default_envs = t-echo
@ -21,7 +21,7 @@ default_envs = tbeam
;default_envs = nano-g1
;default_envs = pca10059_diy_eink
;default_envs = meshtastic-diy-v1
;default_envs = meshtastic-diy-v1.1
;default_envs = meshtastic-diy-v1_1
;default_envs = meshtastic-dr-dev
;default_envs = m5stack-coreink
;default_envs = rak4631
@ -60,7 +60,7 @@ monitor_speed = 115200
lib_deps =
https://github.com/meshtastic/esp8266-oled-ssd1306.git#b38094e03dfa964fbc0e799bc374e91a605c1223 ; ESP8266_SSD1306
mathertel/OneButton@^2.0.3 ; OneButton library for non-blocking button debounce
https://github.com/mathertel/OneButton#2.1.0 ; OneButton library for non-blocking button debounce
https://github.com/meshtastic/arduino-fsm.git#7db3702bf0cfe97b783d6c72595e3f38e0b19159
https://github.com/meshtastic/TinyGPSPlus.git#127ad674ef85f0201cb68a065879653ed94792c4
https://github.com/meshtastic/ArduinoThread.git#72921ac222eed6f526ba1682023cee290d9aa1b3

@ -1 +1 @@
Subproject commit e84f0cc7cab2879b00085000589b9fd6527d0d68
Subproject commit 345b3bf103237503459457ac2b74f4fedf2db102

View File

@ -28,6 +28,7 @@
#define DEBUG_PORT (*console) // Serial debug port
#ifdef USE_SEGGER
#define DEBUG_PORT
#define LOG_DEBUG(...) SEGGER_RTT_printf(0, __VA_ARGS__)
#define LOG_INFO(...) SEGGER_RTT_printf(0, __VA_ARGS__)
#define LOG_WARN(...) SEGGER_RTT_printf(0, __VA_ARGS__)

View File

@ -138,8 +138,9 @@ class GPSStatus : public Status
LOG_DEBUG("New GPS pos@%x:3 lat=%f, lon=%f, alt=%d, pdop=%.2f, track=%.2f, speed=%.2f, sats=%d\n", p.timestamp,
p.latitude_i * 1e-7, p.longitude_i * 1e-7, p.altitude, p.PDOP * 1e-2, p.ground_track * 1e-5,
p.ground_speed * 1e-2, p.sats_in_view);
} else
} else {
LOG_DEBUG("No GPS lock\n");
}
onNewStatus.notifyObservers(this);
}
return 0;

View File

@ -6,6 +6,7 @@
#include "main.h"
#include "sleep.h"
#include "utils.h"
static const char *TAG = "ADCmod";
#ifdef DEBUG_HEAP_MQTT
#include "mqtt/MQTT.h"
@ -17,6 +18,23 @@
#define DELAY_FOREVER portMAX_DELAY
#endif
#if defined(BATTERY_PIN) && defined(ARCH_ESP32)
#ifndef BAT_MEASURE_ADC_UNIT // ADC1 is default
static const adc1_channel_t adc_channel = ADC_CHANNEL;
static const adc_unit_t unit = ADC_UNIT_1;
#else // ADC2
static const adc2_channel_t adc_channel = ADC_CHANNEL;
static const adc_unit_t unit = ADC_UNIT_2;
RTC_NOINIT_ATTR uint64_t RTC_reg_b;
#endif // BAT_MEASURE_ADC_UNIT
esp_adc_cal_characteristics_t *adc_characs = (esp_adc_cal_characteristics_t *)calloc(1, sizeof(esp_adc_cal_characteristics_t));
static const adc_atten_t atten = ADC_ATTEN_DB_11;
#endif // BATTERY_PIN && ARCH_ESP32
#ifdef HAS_PMU
#include "XPowersAXP192.tpp"
#include "XPowersAXP2101.tpp"
@ -128,18 +146,41 @@ class AnalogBatteryLevel : public HasBatteryLevel
// Set the number of samples, it has an effect of increasing sensitivity, especially in complex electromagnetic
// environment.
uint32_t raw = 0;
#ifdef ARCH_ESP32
#ifndef BAT_MEASURE_ADC_UNIT // ADC1
for (int i = 0; i < BATTERY_SENSE_SAMPLES; i++) {
raw += adc1_get_raw(adc_channel);
}
#else // ADC2
int32_t adc_buf = 0;
for (int i = 0; i < BATTERY_SENSE_SAMPLES; i++) {
// ADC2 wifi bug workaround, see
// https://github.com/espressif/arduino-esp32/issues/102
WRITE_PERI_REG(SENS_SAR_READ_CTRL2_REG, RTC_reg_b);
SET_PERI_REG_MASK(SENS_SAR_READ_CTRL2_REG, SENS_SAR2_DATA_INV);
adc2_get_raw(adc_channel, ADC_WIDTH_BIT_12, &adc_buf);
raw += adc_buf;
}
#endif // BAT_MEASURE_ADC_UNIT
#else // !ARCH_ESP32
for (uint32_t i = 0; i < BATTERY_SENSE_SAMPLES; i++) {
raw += analogRead(BATTERY_PIN);
}
#endif
raw = raw / BATTERY_SENSE_SAMPLES;
float scaled;
#ifdef ARCH_ESP32
scaled = esp_adc_cal_raw_to_voltage(raw, adc_characs);
scaled *= operativeAdcMultiplier;
#else
#ifndef VBAT_RAW_TO_SCALED
scaled = 1000.0 * operativeAdcMultiplier * (AREF_VOLTAGE / 1024.0) * raw;
#else
scaled = VBAT_RAW_TO_SCALED(raw); // defined in variant.h
#endif
#endif // VBAT RAW TO SCALED
#endif // ARCH_ESP32
// LOG_DEBUG("battery gpio %d raw val=%u scaled=%u\n", BATTERY_PIN, raw, (uint32_t)(scaled));
last_read_value = scaled;
return scaled;
} else {
@ -147,7 +188,7 @@ class AnalogBatteryLevel : public HasBatteryLevel
}
#else
return 0;
#endif
#endif // BATTERY_PIN
}
/**
@ -228,25 +269,48 @@ bool Power::analogInit()
// disable any internal pullups
pinMode(BATTERY_PIN, INPUT);
#ifdef ARCH_ESP32
// ESP32 needs special analog stuff
adcAttachPin(BATTERY_PIN);
#ifndef BATTERY_SENSE_RESOLUTION_BITS
#define BATTERY_SENSE_RESOLUTION_BITS 10
#endif
#ifdef ARCH_ESP32 // ESP32 needs special analog stuff
#ifndef ADC_WIDTH // max resolution by default
static const adc_bits_width_t width = ADC_WIDTH_BIT_12;
#else
static const adc_bits_width_t width = ADC_WIDTH;
#endif
#ifndef BAT_MEASURE_ADC_UNIT // ADC1
adc1_config_width(width);
adc1_config_channel_atten(adc_channel, atten);
#else // ADC2
adc2_config_channel_atten(adc_channel, atten);
// ADC2 wifi bug workaround
RTC_reg_b = READ_PERI_REG(SENS_SAR_READ_CTRL2_REG);
#endif
// calibrate ADC
esp_adc_cal_value_t val_type = esp_adc_cal_characterize(unit, atten, width, DEFAULT_VREF, adc_characs);
// show ADC characterization base
if (val_type == ESP_ADC_CAL_VAL_EFUSE_TP) {
ESP_LOGI(TAG, "ADC characterization based on Two Point values stored in eFuse");
} else if (val_type == ESP_ADC_CAL_VAL_EFUSE_VREF) {
ESP_LOGI(TAG, "ADC characterization based on reference voltage stored in eFuse");
} else {
ESP_LOGI(TAG, "ADC characterization based on default reference voltage");
}
#endif // ARCH_ESP32
#ifdef ARCH_NRF52
#ifdef VBAT_AR_INTERNAL
analogReference(VBAT_AR_INTERNAL);
#else
analogReference(AR_INTERNAL); // 3.6V
#endif
#endif
#ifndef BATTERY_SENSE_RESOLUTION_BITS
#define BATTERY_SENSE_RESOLUTION_BITS 10
#endif
// adcStart(BATTERY_PIN);
analogReadResolution(BATTERY_SENSE_RESOLUTION_BITS); // Default of 12 is not very linear. Recommended to use 10 or 11
// depending on needed resolution.
#endif // ARCH_NRF52
batteryLevel = &analogLevel;
return true;
#else
@ -302,7 +366,7 @@ void Power::readPowerStatus()
{
if (batteryLevel) {
bool hasBattery = batteryLevel->isBatteryConnect();
int batteryVoltageMv = 0;
uint32_t batteryVoltageMv = 0;
int8_t batteryChargePercent = 0;
if (hasBattery) {
batteryVoltageMv = batteryLevel->getBattVoltage();
@ -365,8 +429,8 @@ void Power::readPowerStatus()
#endif
// If we have a battery at all and it is less than 10% full, force deep sleep if we have more than 10 low readings in a
// row
// If we have a battery at all and it is less than 10% full, force deep sleep if we have more than 10 low readings in
// a row
if (powerStatus2.getHasBattery() && !powerStatus2.getHasUSB()) {
if (batteryLevel->getBattVoltage() < MIN_BAT_MILLIVOLTS) {
low_voltage_counter++;
@ -444,10 +508,10 @@ int32_t Power::runOnce()
* Init the power manager chip
*
* axp192 power
DCDC1 0.7-3.5V @ 1200mA max -> OLED // If you turn this off you'll lose comms to the axp192 because the OLED and the axp192
share the same i2c bus, instead use ssd1306 sleep mode DCDC2 -> unused DCDC3 0.7-3.5V @ 700mA max -> ESP32 (keep this on!) LDO1
30mA -> charges GPS backup battery // charges the tiny J13 battery by the GPS to power the GPS ram (for a couple of days), can
not be turned off LDO2 200mA -> LORA LDO3 200mA -> GPS
DCDC1 0.7-3.5V @ 1200mA max -> OLED // If you turn this off you'll lose comms to the axp192 because the OLED and the
axp192 share the same i2c bus, instead use ssd1306 sleep mode DCDC2 -> unused DCDC3 0.7-3.5V @ 700mA max -> ESP32 (keep this
on!) LDO1 30mA -> charges GPS backup battery // charges the tiny J13 battery by the GPS to power the GPS ram (for a couple of
days), can not be turned off LDO2 200mA -> LORA LDO3 200mA -> GPS
*
*/
bool Power::axpChipInit()
@ -574,7 +638,8 @@ bool Power::axpChipInit()
// t-beam s3 core
/**
* gnss module power channel
* The default ALDO4 is off, you need to turn on the GNSS power first, otherwise it will be invalid during initialization
* The default ALDO4 is off, you need to turn on the GNSS power first, otherwise it will be invalid during
* initialization
*/
PMU->setPowerChannelVoltage(XPOWERS_ALDO4, 3300);
PMU->enablePowerOutput(XPOWERS_ALDO4);

View File

@ -31,12 +31,14 @@ IRAM_ATTR bool NotifiedWorkerThread::notifyCommon(uint32_t v, bool overwrite)
runASAP = true;
notification = v;
if (debugNotification)
if (debugNotification) {
LOG_DEBUG("setting notification %d\n", v);
}
return true;
} else {
if (debugNotification)
if (debugNotification) {
LOG_DEBUG("dropping notification %d\n", v);
}
return false;
}
}
@ -64,9 +66,10 @@ bool NotifiedWorkerThread::notifyLater(uint32_t delay, uint32_t v, bool overwrit
if (didIt) { // If we didn't already have something queued, override the delay to be larger
setIntervalFromNow(delay); // a new version of setInterval relative to the current time
if (debugNotification)
if (debugNotification) {
LOG_DEBUG("delaying notification %u\n", delay);
}
}
return didIt;
}

View File

@ -61,14 +61,17 @@ bool OSThread::shouldRun(unsigned long time)
{
bool r = Thread::shouldRun(time);
if (showRun && r)
if (showRun && r) {
LOG_DEBUG("Thread %s: run\n", ThreadName.c_str());
}
if (showWaiting && enabled && !r)
if (showWaiting && enabled && !r) {
LOG_DEBUG("Thread %s: wait %lu\n", ThreadName.c_str(), interval);
}
if (showDisabled && !enabled)
if (showDisabled && !enabled) {
LOG_DEBUG("Thread %s: disabled\n", ThreadName.c_str());
}
return r;
}

View File

@ -1239,8 +1239,10 @@ void Screen::setFrames()
moduleFrames = MeshModule::GetMeshModulesWithUIFrames();
LOG_DEBUG("Showing %d module frames\n", moduleFrames.size());
#ifdef DEBUG_PORT
int totalFrameCount = MAX_NUM_NODES + NUM_EXTRA_FRAMES + moduleFrames.size();
LOG_DEBUG("Total frame count: %d\n", totalFrameCount);
#endif
// We don't show the node info our our node (if we have it yet - we should)
size_t numnodes = nodeDB.getNumNodes();

View File

@ -462,10 +462,11 @@ void setup()
gps = createGps();
if (gps)
if (gps) {
gpsStatus->observe(&gps->newStatus);
else
} else {
LOG_WARN("No GPS found - running without GPS\n");
}
nodeStatus->observe(&nodeDB.newStatus);

View File

@ -108,8 +108,9 @@ CryptoKey Channels::getKey(ChannelIndex chIndex)
if (ch.role == meshtastic_Channel_Role_SECONDARY) {
LOG_DEBUG("Unset PSK for secondary channel %s. using primary key\n", ch.settings.name);
k = getKey(primaryIndex);
} else
} else {
LOG_WARN("User disabled encryption\n");
}
} else if (k.length == 1) {
// Convert the short single byte variants of psk into variant that can be used more generally

View File

@ -179,10 +179,11 @@ void MeshModule::callPlugins(const meshtastic_MeshPacket &mp, RxSource src)
}
}
if (!moduleFound)
if (!moduleFound) {
LOG_DEBUG("No modules interested in portnum=%d, src=%s\n", mp.decoded.portnum,
(src == RX_SRC_LOCAL) ? "LOCAL" : "REMOTE");
}
}
meshtastic_MeshPacket *MeshModule::allocReply()
{

View File

@ -468,9 +468,10 @@ void NodeDB::loadFromDisk()
}
}
if (loadProto(oemConfigFile, meshtastic_OEMStore_size, sizeof(meshtastic_OEMStore), &meshtastic_OEMStore_msg, &oemStore))
if (loadProto(oemConfigFile, meshtastic_OEMStore_size, sizeof(meshtastic_OEMStore), &meshtastic_OEMStore_msg, &oemStore)) {
LOG_INFO("Loaded OEMStore\n");
}
}
/** Save a protobuf from a file, return true for success */
bool NodeDB::saveProto(const char *filename, size_t protoSize, const pb_msgdesc_t *fields, const void *dest_struct)
@ -494,10 +495,12 @@ bool NodeDB::saveProto(const char *filename, size_t protoSize, const pb_msgdesc_
f.close();
// brief window of risk here ;-)
if (FSCom.exists(filename) && !FSCom.remove(filename))
if (FSCom.exists(filename) && !FSCom.remove(filename)) {
LOG_WARN("Can't remove old pref file\n");
if (!renameFile(filenameTmp.c_str(), filename))
}
if (!renameFile(filenameTmp.c_str(), filename)) {
LOG_ERROR("Error: can't rename new pref file\n");
}
} else {
LOG_ERROR("Can't write prefs\n");
#ifdef ARCH_NRF52
@ -802,10 +805,11 @@ void recordCriticalError(meshtastic_CriticalErrorCode code, uint32_t address, co
// Print error to screen and serial port
String lcd = String("Critical error ") + code + "!\n";
screen->print(lcd.c_str());
if (filename)
if (filename) {
LOG_ERROR("NOTE! Recording critical error %d at %s:%lu\n", code, filename, address);
else
} else {
LOG_ERROR("NOTE! Recording critical error %d, address=0x%lx\n", code, address);
}
// Record error to DB
myNodeInfo.error_code = code;

View File

@ -423,8 +423,9 @@ int PhoneAPI::onNotify(uint32_t newValue)
if (state == STATE_SEND_PACKETS) {
LOG_INFO("Telling client we have new packets %u\n", newValue);
onNowHasData(newValue);
} else
} else {
LOG_DEBUG("(Client not yet interested in packets)\n");
}
return 0;
}

View File

@ -241,6 +241,7 @@ uint32_t RadioInterface::getTxDelayMsecWeighted(float snr)
void printPacket(const char *prefix, const meshtastic_MeshPacket *p)
{
#ifdef DEBUG_PORT
std::string out = DEBUG_PORT.mt_sprintf("%s (id=0x%08x fr=0x%02x to=0x%02x, WantAck=%d, HopLim=%d Ch=0x%x", prefix, p->id,
p->from & 0xff, p->to & 0xff, p->want_ack, p->hop_limit, p->channel);
if (p->which_payload_variant == meshtastic_MeshPacket_decoded_tag) {
@ -283,6 +284,7 @@ void printPacket(const char *prefix, const meshtastic_MeshPacket *p)
out += ")";
LOG_DEBUG("%s\n", out.c_str());
#endif
}
RadioInterface::RadioInterface()

View File

@ -78,8 +78,9 @@ bool RadioLibInterface::canSendImmediately()
bool busyRx = isReceiving && isActivelyReceiving();
if (busyTx || busyRx) {
if (busyTx)
if (busyTx) {
LOG_WARN("Can not send yet, busyTx\n");
}
// If we've been trying to send the same packet more than one minute and we haven't gotten a
// TX IRQ from the radio, the radio is probably broken.
if (busyTx && (millis() - lastTxStart > 60000)) {
@ -88,8 +89,9 @@ bool RadioLibInterface::canSendImmediately()
// reboot in 5 seconds when this condition occurs.
rebootAtMsec = lastTxStart + 65000;
}
if (busyRx)
if (busyRx) {
LOG_WARN("Can not send yet, busyRx\n");
}
return false;
} else
return true;
@ -164,9 +166,9 @@ meshtastic_QueueStatus RadioLibInterface::getQueueStatus()
bool RadioLibInterface::canSleep()
{
bool res = txQueue.empty();
if (!res) // only print debug messages if we are vetoing sleep
if (!res) { // only print debug messages if we are vetoing sleep
LOG_DEBUG("radio wait to sleep, txEmpty=%d\n", res);
}
return res;
}

View File

@ -104,14 +104,15 @@ void ReliableRouter::sniffReceived(const meshtastic_MeshPacket *p, const meshtas
if (p->to == ourNode) { // ignore ack/nak/want_ack packets that are not address to us (we only handle 0 hop reliability)
if (p->want_ack) {
if (MeshModule::currentReply)
if (MeshModule::currentReply) {
LOG_DEBUG("Some other module has replied to this message, no need for a 2nd ack\n");
else if (p->which_payload_variant == meshtastic_MeshPacket_decoded_tag)
} else if (p->which_payload_variant == meshtastic_MeshPacket_decoded_tag) {
sendAckNak(meshtastic_Routing_Error_NONE, getFrom(p), p->id, p->channel);
else
} else {
// Send a 'NO_CHANNEL' error on the primary channel if want_ack packet destined for us cannot be decoded
sendAckNak(meshtastic_Routing_Error_NO_CHANNEL, getFrom(p), p->id, channels.getPrimaryIndex());
}
}
// We consider an ack to be either a !routing packet with a request ID or a routing packet with !error
PacketId ackId = ((c && c->error_reason == meshtastic_Routing_Error_NONE) || !c) ? p->decoded.request_id : 0;

View File

@ -211,8 +211,10 @@ ErrorCode Router::send(meshtastic_MeshPacket *p)
if (!config.lora.override_duty_cycle && myRegion->dutyCycle < 100) {
float hourlyTxPercent = airTime->utilizationTXPercent();
if (hourlyTxPercent > myRegion->dutyCycle) {
#ifdef DEBUG_PORT
uint8_t silentMinutes = airTime->getSilentMinutes(hourlyTxPercent, myRegion->dutyCycle);
LOG_WARN("Duty cycle limit exceeded. Aborting send for now, you can send again in %d minutes.\n", silentMinutes);
#endif
meshtastic_Routing_Error err = meshtastic_Routing_Error_DUTY_CYCLE_LIMIT;
if (getFrom(p) == nodeDB.getNodeNum()) { // only send NAK to API, not to the mesh
abortSendAndNak(err, p);
@ -479,9 +481,9 @@ void Router::perhapsHandleReceived(meshtastic_MeshPacket *p)
// assert(radioConfig.has_preferences);
bool ignore = is_in_repeated(config.lora.ignore_incoming, p->from);
if (ignore)
if (ignore) {
LOG_DEBUG("Ignoring incoming message, 0x%x is in our ignore list\n", p->from);
else if (ignore |= shouldFilterReceived(p)) {
} else if (ignore |= shouldFilterReceived(p)) {
LOG_DEBUG("Incoming message was filtered 0x%x\n", p->from);
}

View File

@ -60,16 +60,19 @@ template <typename T> bool SX126xInterface<T>::init()
LOG_DEBUG("Current limit set to %f\n", currentLimit);
LOG_DEBUG("Current limit set result %d\n", res);
#ifdef SX126X_E22
#if defined(SX126X_E22)
// E22 Emulation explicitly requires DIO2 as RF switch, so set it to TRUE again for good measure. In case somebody defines
// SX126X_TX for an E22 Module
if (res == RADIOLIB_ERR_NONE)
if (res == RADIOLIB_ERR_NONE) {
LOG_DEBUG("SX126X_E22 mode enabled. Setting DIO2 as RF Switch\n");
res = lora.setDio2AsRfSwitch(true);
}
#endif
#if defined(SX126X_TXEN) && (SX126X_TXEN != RADIOLIB_NC)
// lora.begin sets Dio2 as RF switch control, which is not true if we are manually controlling RX and TX
if (res == RADIOLIB_ERR_NONE) {
LOG_DEBUG("SX126X_TX/RX EN pins defined. Setting RF Switch: RXEN=%i, TXEN=%i\n", SX126X_RXEN, SX126X_TXEN);
res = lora.setDio2AsRfSwitch(false);
lora.setRfSwitchPins(SX126X_RXEN, SX126X_TXEN);
}
@ -176,8 +179,9 @@ template <typename T> void SX126xInterface<T>::setStandby()
int err = lora.standby();
if (err != RADIOLIB_ERR_NONE)
if (err != RADIOLIB_ERR_NONE) {
LOG_DEBUG("SX126x standby failed with error %d\n", err);
}
assert(err == RADIOLIB_ERR_NONE);

View File

@ -151,8 +151,9 @@ template <typename T> void SX128xInterface<T>::setStandby()
int err = lora.standby();
if (err != RADIOLIB_ERR_NONE)
if (err != RADIOLIB_ERR_NONE) {
LOG_ERROR("SX128x standby failed with error %d\n", err);
}
assert(err == RADIOLIB_ERR_NONE);

View File

@ -233,6 +233,9 @@ typedef struct _meshtastic_Config_DeviceConfig {
uint32_t node_info_broadcast_secs;
/* Treat double tap interrupt on supported accelerometers as a button press if set to true */
bool double_tap_as_button_press;
/* If true, device is considered to be "managed" by a mesh administrator
Clients should then limit available configuration and administrative options inside the user interface */
bool is_managed;
} meshtastic_Config_DeviceConfig;
/* Position Config */
@ -529,7 +532,7 @@ extern "C" {
/* Initializer values for message structs */
#define meshtastic_Config_init_default {0, {meshtastic_Config_DeviceConfig_init_default}}
#define meshtastic_Config_DeviceConfig_init_default {_meshtastic_Config_DeviceConfig_Role_MIN, 0, 0, 0, 0, _meshtastic_Config_DeviceConfig_RebroadcastMode_MIN, 0, 0}
#define meshtastic_Config_DeviceConfig_init_default {_meshtastic_Config_DeviceConfig_Role_MIN, 0, 0, 0, 0, _meshtastic_Config_DeviceConfig_RebroadcastMode_MIN, 0, 0, 0}
#define meshtastic_Config_PositionConfig_init_default {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
#define meshtastic_Config_PowerConfig_init_default {0, 0, 0, 0, 0, 0, 0, 0}
#define meshtastic_Config_NetworkConfig_init_default {0, "", "", "", 0, _meshtastic_Config_NetworkConfig_AddressMode_MIN, false, meshtastic_Config_NetworkConfig_IpV4Config_init_default, ""}
@ -538,7 +541,7 @@ extern "C" {
#define meshtastic_Config_LoRaConfig_init_default {0, _meshtastic_Config_LoRaConfig_ModemPreset_MIN, 0, 0, 0, 0, _meshtastic_Config_LoRaConfig_RegionCode_MIN, 0, 0, 0, 0, 0, 0, 0, 0, {0, 0, 0}}
#define meshtastic_Config_BluetoothConfig_init_default {0, _meshtastic_Config_BluetoothConfig_PairingMode_MIN, 0}
#define meshtastic_Config_init_zero {0, {meshtastic_Config_DeviceConfig_init_zero}}
#define meshtastic_Config_DeviceConfig_init_zero {_meshtastic_Config_DeviceConfig_Role_MIN, 0, 0, 0, 0, _meshtastic_Config_DeviceConfig_RebroadcastMode_MIN, 0, 0}
#define meshtastic_Config_DeviceConfig_init_zero {_meshtastic_Config_DeviceConfig_Role_MIN, 0, 0, 0, 0, _meshtastic_Config_DeviceConfig_RebroadcastMode_MIN, 0, 0, 0}
#define meshtastic_Config_PositionConfig_init_zero {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
#define meshtastic_Config_PowerConfig_init_zero {0, 0, 0, 0, 0, 0, 0, 0}
#define meshtastic_Config_NetworkConfig_init_zero {0, "", "", "", 0, _meshtastic_Config_NetworkConfig_AddressMode_MIN, false, meshtastic_Config_NetworkConfig_IpV4Config_init_zero, ""}
@ -556,6 +559,7 @@ extern "C" {
#define meshtastic_Config_DeviceConfig_rebroadcast_mode_tag 6
#define meshtastic_Config_DeviceConfig_node_info_broadcast_secs_tag 7
#define meshtastic_Config_DeviceConfig_double_tap_as_button_press_tag 8
#define meshtastic_Config_DeviceConfig_is_managed_tag 9
#define meshtastic_Config_PositionConfig_position_broadcast_secs_tag 1
#define meshtastic_Config_PositionConfig_position_broadcast_smart_enabled_tag 2
#define meshtastic_Config_PositionConfig_fixed_position_tag 3
@ -650,7 +654,8 @@ X(a, STATIC, SINGULAR, UINT32, button_gpio, 4) \
X(a, STATIC, SINGULAR, UINT32, buzzer_gpio, 5) \
X(a, STATIC, SINGULAR, UENUM, rebroadcast_mode, 6) \
X(a, STATIC, SINGULAR, UINT32, node_info_broadcast_secs, 7) \
X(a, STATIC, SINGULAR, BOOL, double_tap_as_button_press, 8)
X(a, STATIC, SINGULAR, BOOL, double_tap_as_button_press, 8) \
X(a, STATIC, SINGULAR, BOOL, is_managed, 9)
#define meshtastic_Config_DeviceConfig_CALLBACK NULL
#define meshtastic_Config_DeviceConfig_DEFAULT NULL
@ -765,7 +770,7 @@ extern const pb_msgdesc_t meshtastic_Config_BluetoothConfig_msg;
/* Maximum encoded size of messages (where known) */
#define meshtastic_Config_BluetoothConfig_size 10
#define meshtastic_Config_DeviceConfig_size 28
#define meshtastic_Config_DeviceConfig_size 30
#define meshtastic_Config_DisplayConfig_size 28
#define meshtastic_Config_LoRaConfig_size 77
#define meshtastic_Config_NetworkConfig_IpV4Config_size 20

View File

@ -196,7 +196,7 @@ extern const pb_msgdesc_t meshtastic_OEMStore_msg;
/* Maximum encoded size of messages (where known) */
#define meshtastic_ChannelFile_size 638
#define meshtastic_DeviceState_size 22364
#define meshtastic_OEMStore_size 3041
#define meshtastic_OEMStore_size 3043
#ifdef __cplusplus
} /* extern "C" */

View File

@ -156,7 +156,7 @@ extern const pb_msgdesc_t meshtastic_LocalModuleConfig_msg;
#define meshtastic_LocalModuleConfig_fields &meshtastic_LocalModuleConfig_msg
/* Maximum encoded size of messages (where known) */
#define meshtastic_LocalConfig_size 456
#define meshtastic_LocalConfig_size 458
#define meshtastic_LocalModuleConfig_size 439
#ifdef __cplusplus

View File

@ -112,8 +112,9 @@ meshtastic_MeshPacket *PositionModule::allocReply()
if (getRTCQuality() < RTCQualityDevice) {
LOG_INFO("Stripping time %u from position send\n", p.time);
p.time = 0;
} else
} else {
LOG_INFO("Providing time to mesh %u\n", p.time);
}
LOG_INFO("Position reply: time=%i, latI=%i, lonI=-%i\n", p.time, p.latitude_i, p.longitude_i);

View File

@ -8,10 +8,12 @@
meshtastic_MeshPacket *ReplyModule::allocReply()
{
assert(currentRequest); // should always be !NULL
#ifdef DEBUG_PORT
auto req = *currentRequest;
auto &p = req.decoded;
// The incoming message is in p.payload
LOG_INFO("Received message from=0x%0x, id=%d, msg=%.*s\n", req.from, req.id, p.payload.size, p.payload.bytes);
#endif
screen->print("Sending reply\n");

View File

@ -59,6 +59,7 @@ int32_t AirQualityTelemetryModule::runOnce()
bool AirQualityTelemetryModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshtastic_Telemetry *t)
{
if (t->which_variant == meshtastic_Telemetry_air_quality_metrics_tag) {
#ifdef DEBUG_PORT
const char *sender = getSenderShortName(mp);
LOG_INFO("(Received from %s): pm10_standard=%i, pm25_standard=%i, pm100_standard=%i\n", sender,
@ -68,7 +69,7 @@ bool AirQualityTelemetryModule::handleReceivedProtobuf(const meshtastic_MeshPack
LOG_INFO(" | PM1.0(Environmental)=%i, PM2.5(Environmental)=%i, PM10.0(Environmental)=%i\n",
t->variant.air_quality_metrics.pm10_environmental, t->variant.air_quality_metrics.pm25_environmental,
t->variant.air_quality_metrics.pm100_environmental);
#endif
// release previous packet before occupying a new spot
if (lastMeasurementPacket != nullptr)
packetPool.release(lastMeasurementPacket);

View File

@ -31,12 +31,13 @@ int32_t DeviceTelemetryModule::runOnce()
bool DeviceTelemetryModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshtastic_Telemetry *t)
{
if (t->which_variant == meshtastic_Telemetry_device_metrics_tag) {
#ifdef DEBUG_PORT
const char *sender = getSenderShortName(mp);
LOG_INFO("(Received from %s): air_util_tx=%f, channel_utilization=%f, battery_level=%i, voltage=%f\n", sender,
t->variant.device_metrics.air_util_tx, t->variant.device_metrics.channel_utilization,
t->variant.device_metrics.battery_level, t->variant.device_metrics.voltage);
#endif
nodeDB.updateTelemetry(getFrom(&mp), *t, RX_SRC_RADIO);
}
return false; // Let others look at this message also if they want

View File

@ -183,6 +183,7 @@ void EnvironmentTelemetryModule::drawFrame(OLEDDisplay *display, OLEDDisplayUiSt
bool EnvironmentTelemetryModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshtastic_Telemetry *t)
{
if (t->which_variant == meshtastic_Telemetry_environment_metrics_tag) {
#ifdef DEBUG_PORT
const char *sender = getSenderShortName(mp);
LOG_INFO("(Received from %s): barometric_pressure=%f, current=%f, gas_resistance=%f, relative_humidity=%f, "
@ -190,7 +191,7 @@ bool EnvironmentTelemetryModule::handleReceivedProtobuf(const meshtastic_MeshPac
sender, t->variant.environment_metrics.barometric_pressure, t->variant.environment_metrics.current,
t->variant.environment_metrics.gas_resistance, t->variant.environment_metrics.relative_humidity,
t->variant.environment_metrics.temperature, t->variant.environment_metrics.voltage);
#endif
// release previous packet before occupying a new spot
if (lastMeasurementPacket != nullptr)
packetPool.release(lastMeasurementPacket);

View File

@ -92,10 +92,12 @@ void BME680Sensor::updateState()
file.flush();
file.close();
// brief window of risk here ;-)
if (FSCom.exists(bsecConfigFileName) && !FSCom.remove(bsecConfigFileName))
if (FSCom.exists(bsecConfigFileName) && !FSCom.remove(bsecConfigFileName)) {
LOG_WARN("Can't remove old state file\n");
if (!renameFile(filenameTmp.c_str(), bsecConfigFileName))
}
if (!renameFile(filenameTmp.c_str(), bsecConfigFileName)) {
LOG_ERROR("Error: can't rename new state file\n");
}
} else {
LOG_INFO("Can't write %s state (File: %s).\n", sensorName, bsecConfigFileName);

View File

@ -7,8 +7,10 @@ TextMessageModule *textMessageModule;
ProcessMessage TextMessageModule::handleReceived(const meshtastic_MeshPacket &mp)
{
#ifdef DEBUG_PORT
auto &p = mp.decoded;
LOG_INFO("Received text msg from=0x%0x, id=0x%x, msg=%.*s\n", mp.from, mp.id, p.payload.size, p.payload.bytes);
#endif
// We only store/display messages destined for us.
// Keep a copy of the most recent text message.

View File

@ -47,6 +47,7 @@ void TraceRouteModule::appendMyID(meshtastic_RouteDiscovery *updated)
void TraceRouteModule::printRoute(meshtastic_RouteDiscovery *r, uint32_t origin, uint32_t dest)
{
#ifdef DEBUG_PORT
LOG_INFO("Route traced:\n");
LOG_INFO("0x%x --> ", origin);
for (uint8_t i = 0; i < r->route_count; i++) {
@ -56,6 +57,7 @@ void TraceRouteModule::printRoute(meshtastic_RouteDiscovery *r, uint32_t origin,
LOG_INFO("0x%x\n", dest);
else
LOG_INFO("...\n");
#endif
}
meshtastic_MeshPacket *TraceRouteModule::allocReply()

View File

@ -7,8 +7,10 @@ WaypointModule *waypointModule;
ProcessMessage WaypointModule::handleReceived(const meshtastic_MeshPacket &mp)
{
#ifdef DEBUG_PORT
auto &p = mp.decoded;
LOG_INFO("Received waypoint msg from=0x%0x, id=0x%x, msg=%.*s\n", mp.from, mp.id, p.payload.size, p.payload.bytes);
#endif
// We only store/display messages destined for us.
// Keep a copy of the most recent text message.

View File

@ -195,8 +195,9 @@ int32_t AudioModule::runOnce()
.tx_desc_auto_clear = true,
.fixed_mclk = 0};
res = i2s_driver_install(I2S_PORT, &i2s_config, 0, NULL);
if (res != ESP_OK)
if (res != ESP_OK) {
LOG_ERROR("Failed to install I2S driver: %d\n", res);
}
const i2s_pin_config_t pin_config = {
.bck_io_num = moduleConfig.audio.i2s_sck,
@ -204,12 +205,14 @@ int32_t AudioModule::runOnce()
.data_out_num = moduleConfig.audio.i2s_din ? moduleConfig.audio.i2s_din : I2S_PIN_NO_CHANGE,
.data_in_num = moduleConfig.audio.i2s_sd ? moduleConfig.audio.i2s_sd : I2S_PIN_NO_CHANGE};
res = i2s_set_pin(I2S_PORT, &pin_config);
if (res != ESP_OK)
if (res != ESP_OK) {
LOG_ERROR("Failed to set I2S pin config: %d\n", res);
}
res = i2s_start(I2S_PORT);
if (res != ESP_OK)
if (res != ESP_OK) {
LOG_ERROR("Failed to start I2S: %d\n", res);
}
radio_state = RadioState::rx;

View File

@ -53,6 +53,7 @@ int32_t RangeTestModule::runOnce()
if (moduleConfig.range_test.sender) {
LOG_INFO("Initializing Range Test Module -- Sender\n");
started = millis(); // make a note of when we started
return (5000); // Sending first message 5 seconds after initilization.
} else {
LOG_INFO("Initializing Range Test Module -- Receiver\n");
@ -77,7 +78,13 @@ int32_t RangeTestModule::runOnce()
rangeTestModuleRadio->sendPayload();
}
// If we have been running for more than 8 hours, turn module back off
if (millis() - started > 28800000) {
LOG_INFO("Range Test Module - Disabling after 8 hours\n");
return disable();
} else {
return (senderHeartbeat);
}
} else {
return disable();
// This thread does not need to run as a receiver

View File

@ -9,6 +9,7 @@
class RangeTestModule : private concurrency::OSThread
{
bool firstTime = 1;
unsigned long started = 0;
public:
RangeTestModule();

View File

@ -461,8 +461,9 @@ std::string MQTT::downstreamPacketToJson(meshtastic_MeshPacket *mp)
msgPayload["current"] = new JSONValue(decoded->variant.environment_metrics.current);
}
jsonObj["payload"] = new JSONValue(msgPayload);
} else
} else {
LOG_ERROR("Error decoding protobuf for telemetry message!\n");
}
};
break;
}
@ -479,8 +480,9 @@ std::string MQTT::downstreamPacketToJson(meshtastic_MeshPacket *mp)
msgPayload["shortname"] = new JSONValue(decoded->short_name);
msgPayload["hardware"] = new JSONValue(decoded->hw_model);
jsonObj["payload"] = new JSONValue(msgPayload);
} else
} else {
LOG_ERROR("Error decoding protobuf for nodeinfo message!\n");
}
};
break;
}
@ -503,6 +505,15 @@ std::string MQTT::downstreamPacketToJson(meshtastic_MeshPacket *mp)
if ((int)decoded->altitude) {
msgPayload["altitude"] = new JSONValue((int)decoded->altitude);
}
if ((int)decoded->ground_speed) {
msgPayload["ground_speed"] = new JSONValue((int)decoded->ground_speed);
}
if (int(decoded->ground_track)) {
msgPayload["ground_track"] = new JSONValue((int)decoded->ground_track);
}
if (int(decoded->sats_in_view)) {
msgPayload["sats_in_view"] = new JSONValue((int)decoded->sats_in_view);
}
jsonObj["payload"] = new JSONValue(msgPayload);
} else {
LOG_ERROR("Error decoding protobuf for position message!\n");

View File

@ -39,6 +39,9 @@
#ifndef HAS_CPU_SHUTDOWN
#define HAS_CPU_SHUTDOWN 1
#endif
#ifndef DEFAULT_VREF
#define DEFAULT_VREF 1100
#endif
#if defined(HAS_AXP192) || defined(HAS_AXP2101)
#define HAS_PMU

View File

@ -1,7 +1,10 @@
#pragma once
#include "PowerStatus.h"
#include "concurrency/OSThread.h"
#ifdef ARCH_ESP32
#include <esp_adc_cal.h>
#include <soc/adc_channel.h>
#endif
/**
* Per @spattinson
* MIN_BAT_MILLIVOLTS seems high. Typical 18650 are different chemistry to LiPo, even for LiPos that chart seems a bit off, other
@ -14,6 +17,10 @@
#define BAT_MILLIVOLTS_FULL 4100
#define BAT_MILLIVOLTS_EMPTY 3500
#ifdef BAT_MEASURE_ADC_UNIT
extern RTC_NOINIT_ATTR uint64_t RTC_reg_b;
#include "soc/sens_reg.h" // needed for adc pin reset
#endif
class Power : private concurrency::OSThread
{

View File

@ -132,6 +132,7 @@ void initDeepSleep()
support busted boards, assume button one was pressed wakeButtons = ((uint64_t)1) << buttons.gpios[0];
*/
#ifdef DEBUG_PORT
// If we booted because our timer ran out or the user pressed reset, send those as fake events
const char *reason = "reset"; // our best guess
RESET_REASON hwReason = rtc_get_reset_reason(0);
@ -150,6 +151,7 @@ void initDeepSleep()
LOG_INFO("Booted, wake cause %d (boot count %d), reset_reason=%s\n", wakeCause, bootCount, reason);
#endif
#endif
}
bool doPreflightSleep()
@ -329,23 +331,27 @@ esp_sleep_wakeup_cause_t doLightSleep(uint64_t sleepMsec) // FIXME, use a more r
gpio_wakeup_enable((gpio_num_t)PMU_IRQ, GPIO_INTR_LOW_LEVEL); // pmu irq
#endif
auto res = esp_sleep_enable_gpio_wakeup();
if (res != ESP_OK)
if (res != ESP_OK) {
LOG_DEBUG("esp_sleep_enable_gpio_wakeup result %d\n", res);
}
assert(res == ESP_OK);
res = esp_sleep_enable_timer_wakeup(sleepUsec);
if (res != ESP_OK)
if (res != ESP_OK) {
LOG_DEBUG("esp_sleep_enable_timer_wakeup result %d\n", res);
}
assert(res == ESP_OK);
res = esp_light_sleep_start();
if (res != ESP_OK)
if (res != ESP_OK) {
LOG_DEBUG("esp_light_sleep_start result %d\n", res);
}
assert(res == ESP_OK);
esp_sleep_wakeup_cause_t cause = esp_sleep_get_wakeup_cause();
#ifdef BUTTON_PIN
if (cause == ESP_SLEEP_WAKEUP_GPIO)
if (cause == ESP_SLEEP_WAKEUP_GPIO) {
LOG_INFO("Exit light sleep gpio: btn=%d\n",
!digitalRead(config.device.button_gpio ? config.device.button_gpio : BUTTON_PIN));
}
#endif
return cause;

View File

@ -2,6 +2,8 @@
#define HAS_SCREEN 0
#define I2C_SDA 4
#define I2C_SCL 5
#define BATTERY_PIN 34
#define ADC_CHANNEL ADC1_GPIO34_CHANNEL
// GPS
#undef GPS_RX_PIN

View File

@ -11,6 +11,7 @@
#define BUTTON_PIN 39 // The middle button GPIO on the T-Beam
#define BATTERY_PIN 35 // A battery voltage measurement pin, voltage divider connected here to measure battery voltage
#define ADC_CHANNEL ADC1_GPIO35_CHANNEL
#define ADC_MULTIPLIER 1.85 // (R1 = 470k, R2 = 680k)
#define EXT_PWR_DETECT 4 // Pin to detect connected external power source for LILYGO® TTGO T-Energy T18 and other DIY boards
#define EXT_NOTIFY_OUT 12 // Overridden default pin to use for Ext Notify Module (#975).
@ -38,9 +39,8 @@
#define SX126X_DIO1 LORA_DIO1
#define SX126X_BUSY LORA_DIO2
#define SX126X_RESET LORA_RESET
//#define SX126X_RXEN 14
//#define SX126X_TXEN 13
#define SX126X_POWER_EN (13)
#define SX126X_RXEN RADIOLIB_NC // Defining the RXEN ruins RFSwitching for the E22 900M30S in RadioLib
#define SX126X_TXEN 13
// RX/TX for RFM95/SX127x
#define RF95_RXEN 14

View File

@ -27,3 +27,5 @@
#define ADC_MULTIPLIER 3.2
#define BATTERY_PIN 13 // A battery voltage measurement pin, voltage divider connected here to measure battery voltage
#define ADC_CHANNEL ADC2_GPIO13_CHANNEL
#define BAT_MEASURE_ADC_UNIT 2

View File

@ -30,4 +30,5 @@
#define ADC_MULTIPLIER 3.8
#define BATTERY_PIN 37 // A battery voltage measurement pin, voltage divider connected here to measure battery voltage
#define ADC_CHANNEL ADC1_GPIO37_CHANNEL
#define EXT_NOTIFY_OUT 13 // Default pin to use for Ext Notify Module.

View File

@ -27,3 +27,5 @@
// ratio of voltage divider = 3.20 (R12=100k, R10=220k)
#define ADC_MULTIPLIER 3.2
#define BATTERY_PIN 13 // A battery voltage measurement pin, voltage divider connected here to measure battery voltage
#define ADC_CHANNEL ADC2_GPIO13_CHANNEL
#define BAT_MEASURE_ADC_UNIT 2

View File

@ -8,7 +8,8 @@
#define BUTTON_PIN 0
#define BATTERY_PIN 1 // A battery voltage measurement pin, voltage divider connected here to measure battery voltage
#define ADC_MULTIPLIER 5.22
#define ADC_CHANNEL ADC1_GPIO1_CHANNEL
#define ADC_MULTIPLIER 4.9
#define USE_SX1262

View File

@ -9,7 +9,8 @@
#define BUTTON_PIN 0
#define BATTERY_PIN 1 // A battery voltage measurement pin, voltage divider connected here to measure battery voltage
#define ADC_MULTIPLIER 5.22
#define ADC_CHANNEL ADC1_GPIO1_CHANNEL
#define ADC_MULTIPLIER 4.9
#define USE_SX1262

View File

@ -30,6 +30,7 @@
#endif
#define BATTERY_PIN 35 // A battery voltage measurement pin, voltage divider connected here to measure battery voltage
#define ADC_CHANNEL ADC1_GPIO35_CHANNEL
#define BATTERY_SENSE_SAMPLES 15 // Set the number of samples, It has an effect of increasing sensitivity.
#define ADC_MULTIPLIER 2

View File

@ -33,6 +33,7 @@
#endif
#define BATTERY_PIN 35 // A battery voltage measurement pin, voltage divider connected here to measure battery voltage
#define ADC_CHANNEL ADC1_GPIO35_CHANNEL
#define BATTERY_SENSE_SAMPLES 30 // Set the number of samples, It has an effect of increasing sensitivity.
#define ADC_MULTIPLIER 6.45
#define BAT_FULLVOLT 12600

View File

@ -6,6 +6,7 @@
#define BUTTON_PIN 39
#define BATTERY_PIN 35 // A battery voltage measurement pin, voltage divider connected here to measure battery voltage
#define EXT_NOTIFY_OUT 13 // Default pin to use for Ext Notify Module.
#define ADC_CHANNEL ADC1_GPIO35_CHANNEL
#define USE_RF95
#define LORA_DIO0 26 // a No connect on the SX1262 module

View File

@ -9,6 +9,7 @@
#define BATTERY_PIN 1 // A battery voltage measurement pin, voltage divider connected here to measure battery voltage
// ratio of voltage divider = 2.0 (R42=100k, R43=100k)
#define ADC_MULTIPLIER 2.11 // 2.0 + 10% for correction of display undervoltage.
#define ADC_CHANNEL ADC1_GPIO1_CHANNEL
#define I2C_SDA 18 // I2C pins for this board
#define I2C_SCL 17

View File

@ -4,6 +4,7 @@
#define GPS_TX_PIN 13 // per @eugene
#define BATTERY_PIN 35 // A battery voltage measurement pin, voltage divider connected here to measure battery voltage
#define ADC_CHANNEL ADC1_GPIO35_CHANNEL
#define I2C_SDA 21 // I2C pins for this board
#define I2C_SCL 22

View File

@ -4,6 +4,7 @@
#define GPS_TX_PIN 13 // per @eugene
#define BATTERY_PIN 35 // A battery voltage measurement pin, voltage divider connected here to measure battery voltage
#define ADC_CHANNEL ADC1_GPIO35_CHANNEL
#define I2C_SDA 21 // I2C pins for this board
#define I2C_SCL 22

View File

@ -3,9 +3,12 @@
#define GPS_RX_PIN 15 // per @der_bear on the forum, 36 is incorrect for this board type and 15 is a better pick
#define GPS_TX_PIN 13
#define BATTERY_PIN 35 // A battery voltage measurement pin, voltage divider connected here to measure battery voltage
#define BATTERY_PIN 35
#define ADC_CHANNEL ADC1_GPIO35_CHANNEL
#define BATTERY_SENSE_SAMPLES 30
// ratio of voltage divider = 2.0 (R42=100k, R43=100k)
#define ADC_MULTIPLIER 2.11 // 2.0 + 10% for correction of display undervoltage.
#define ADC_MULTIPLIER 2
#define I2C_SDA 21 // I2C pins for this board
#define I2C_SCL 22

View File

@ -4,6 +4,7 @@
#define BATTERY_PIN 35 // A battery voltage measurement pin, voltage divider connected here to measure battery voltage
// ratio of voltage divider = 2.0 (R42=100k, R43=100k)
#define ADC_MULTIPLIER 2.11 // 2.0 + 10% for correction of display undervoltage.
#define ADC_CHANNEL ADC1_GPIO35_CHANNEL
#define I2C_SDA 21 // I2C pins for this board
#define I2C_SCL 22

View File

@ -1,4 +1,4 @@
[VERSION]
major = 2
minor = 1
build = 12
build = 13