Compare commits

..

36 Commits

Author SHA1 Message Date
Kevin Hester
75281e8c97 Merge pull request #777 from geeksville/dev1.2
Dev1.2
2021-04-02 13:54:20 +08:00
Kevin Hester
8d47e4f3e0 1.2.20 2021-04-02 13:44:53 +08:00
Kevin Hester
92124e1224 Merge remote-tracking branch 'root/master' into dev1.2 2021-04-02 11:13:01 +08:00
Kevin Hester
c798c0032c add frequency_offset 2021-04-02 09:14:12 +08:00
Kevin Hester
2c5ea03b74 fix VFS creation bug in native. fix heap corruption in Fsm free 2021-04-01 20:32:12 +08:00
Kevin Hester
9d452ebf29 add WIP notes about running github actions locally... 2021-04-01 14:12:02 +08:00
Kevin Hester
8a20155214 simplify build 2021-04-01 14:05:27 +08:00
Kevin Hester
6a872b6ac2 remove unused lib from CI build 2021-04-01 13:46:30 +08:00
Kevin Hester
52d61acc23 Merge pull request #776 from geeksville/dev1.2
Dev1.2
2021-03-31 16:49:45 +08:00
Kevin Hester
2594ea0c2c test fix for CI tool 2021-03-31 16:28:16 +08:00
Kevin Hester
9623be1484 fix CI build script typo 2021-03-31 12:08:48 +08:00
Kevin Hester
d810ce0c1e add more time for sim startup 2021-03-31 11:26:19 +08:00
Kevin Hester
efd39c0f49 someone made a boo-boo adding "serial_disabled", caused a nasty NPE 2021-03-31 11:26:00 +08:00
Kevin Hester
5f45a10db5 fix sign comparsion 2021-03-31 11:14:55 +08:00
Kevin Hester
5f948c09fe update libs to fix CI build, thanks @meehow! 2021-03-31 11:05:43 +08:00
Kevin Hester
22f3efd083 update proto 2021-03-31 09:15:41 +08:00
Kevin Hester
88716fc352 Merge remote-tracking branch 'root/master' into dev1.2 2021-03-31 09:14:43 +08:00
Kevin Hester
5c1d8b5bb0 todo updates 2021-03-31 09:13:41 +08:00
Kevin Hester
b68397a911 fix simradio init to work more like real radios 2021-03-30 23:39:51 +08:00
Kevin Hester
5fdcb72d46 cleanup applyModemConfig based on porduino testing, share with sim 2021-03-30 23:34:13 +08:00
Kevin Hester
b70a359fe8 leave phone timeout off a bit longer 2021-03-30 23:11:56 +08:00
Kevin Hester
a9c8564524 fix millisecond unsigned rollover errors found via portduino 2021-03-30 23:11:33 +08:00
Jm Casler
b527e0d447 Merge pull request #774 from mc-hamster/master
Update of #638 - Redid protobuf generation
2021-03-29 17:34:39 -07:00
Jm
d8669f860a Update fo #638 - Redid protobuf generation 2021-03-29 17:33:37 -07:00
Jm Casler
78f104c6de Merge pull request #773 from mc-hamster/master
Fix for #638 - Add option to disable serial interface
2021-03-29 17:12:21 -07:00
Jm
2f8e663f03 Add serial_disabled for #638 2021-03-29 17:08:56 -07:00
Jm Casler
7f7b07ce9d Merge pull request #82 from meshtastic/master
update from master
2021-03-29 17:04:57 -07:00
Kevin Hester
cdb4756d9d fix native build 2021-03-29 20:56:02 +08:00
Kevin Hester
385e291f51 Merge pull request #771 from geeksville/dev1.2
Dev1.2
2021-03-28 12:24:14 +08:00
Kevin Hester
7e60078791 1.2.17 2021-03-28 12:19:49 +08:00
Kevin Hester
073eecd147 Merge remote-tracking branch 'root/master' into dev1.2 2021-03-28 12:16:50 +08:00
Kevin Hester
525fe9b96c dramatically speed up message RX in some cases (we were sleeping much too long) 2021-03-28 12:16:37 +08:00
Kevin Hester
c7f411fc7c remove unused Preferences code (cc @mc-hamster for review)
(noticed because of a compiler warning)
2021-03-28 12:07:43 +08:00
Kevin Hester
fc96500329 fix unused prefs field 2021-03-28 12:06:16 +08:00
Kevin Hester
4e87c4411c fix serious nak bug reported by @havealoha and @luxoon 2021-03-28 11:44:19 +08:00
Kevin Hester
9eb9c473db add note about credit! 2021-03-28 11:43:28 +08:00
31 changed files with 191 additions and 135 deletions

View File

@@ -22,9 +22,6 @@ jobs:
- name: Install extra python tools
run: |
pip install -U adafruit-nrfutil
- name: Install libs needed for linux build
run: |
sudo apt install -y libpsocksxx-dev
- name: Build for tbeam
run: platformio run -e tbeam
- name: Build for heltec
@@ -36,6 +33,7 @@ jobs:
- name: Integration test
run: |
.pio/build/native/program &
sleep 1
sleep 5
echo "Simulator started, launching python test..."
python3 -c 'from meshtastic.test import testSimulator; testSimulator()'

30
.idea/workspace.xml generated
View File

@@ -15,16 +15,13 @@
<component name="ChangeListManager">
<list default="true" id="58922733-b05b-4b90-9655-b9b18914977a" name="Default Changelist" comment="">
<change beforePath="$PROJECT_DIR$/.idea/workspace.xml" beforeDir="false" afterPath="$PROJECT_DIR$/.idea/workspace.xml" afterDir="false" />
<change beforePath="$PROJECT_DIR$/docs/software/TODO.md" beforeDir="false" afterPath="$PROJECT_DIR$/docs/software/TODO.md" afterDir="false" />
<change beforePath="$PROJECT_DIR$/proto" beforeDir="false" afterPath="$PROJECT_DIR$/proto" afterDir="false" />
<change beforePath="$PROJECT_DIR$/src/mesh/generated/mesh.pb.h" beforeDir="false" afterPath="$PROJECT_DIR$/src/mesh/generated/mesh.pb.h" afterDir="false" />
<change beforePath="$PROJECT_DIR$/platformio.ini" beforeDir="false" afterPath="$PROJECT_DIR$/platformio.ini" afterDir="false" />
</list>
<option name="SHOW_DIALOG" value="false" />
<option name="HIGHLIGHT_CONFLICTS" value="true" />
<option name="HIGHLIGHT_NON_ACTIVE_CHANGELIST" value="false" />
<option name="LAST_RESOLUTION" value="IGNORE" />
</component>
<component name="ExecutionTargetManager" SELECTED_TARGET="CMakeBuildProfile:native" />
<component name="Git.Settings">
<option name="RECENT_GIT_ROOT_PATH" value="$PROJECT_DIR$" />
</component>
@@ -49,7 +46,7 @@
<property name="node.js.selected.package.tslint" value="(autodetect)" />
<property name="settings.editor.selected.configurable" value="CMakeSettings" />
</component>
<component name="RunManager" selected="PlatformIO.PlatformIO Upload">
<component name="RunManager" selected="GDB Remote Debug.gdbremote-localhost-2345">
<configuration default="true" type="CLion_Remote" version="1" remoteCommand="tcp:localhost:2345" symbolFile="" sysroot="">
<debugger kind="GDB" isBundled="true" />
<method v="2" />
@@ -63,9 +60,9 @@
<option name="com.jetbrains.cidr.execution.CidrBuildBeforeRunTaskProvider$BuildBeforeRunTask" enabled="true" />
</method>
</configuration>
<configuration default="true" type="GradleAppRunConfiguration" factoryName="Application" REDIRECT_INPUT="false" ELEVATE="false" PASS_PARENT_ENVS_2="true">
<configuration default="true" type="CMakeRunConfiguration" factoryName="Application" REDIRECT_INPUT="false" ELEVATE="false" PASS_PARENT_ENVS_2="true">
<method v="2">
<option name="com.jetbrains.cidr.cpp.gradle.execution.GradleNativeBuildBeforeRunTaskProvider$BuildBeforeRunTask" enabled="true" />
<option name="com.jetbrains.cidr.execution.CidrBuildBeforeRunTaskProvider$BuildBeforeRunTask" enabled="true" />
</method>
</configuration>
<configuration name="PlatformIO Debug" type="platformio" factoryName="PlatformIO Debug" REDIRECT_INPUT="false" ELEVATE="false" PASS_PARENT_ENVS_2="true" PROJECT_NAME="meshtastic-esp32" TARGET_NAME="Debug" CONFIG_NAME="native" RUN_TARGET_PROJECT_NAME="meshtastic-esp32" RUN_TARGET_NAME="Debug">
@@ -96,6 +93,10 @@
<workItem from="1615788663210" duration="6661000" />
<workItem from="1615938346019" duration="1208000" />
<workItem from="1615971126983" duration="5945000" />
<workItem from="1617115374907" duration="357000" />
<workItem from="1617115747078" duration="1391000" />
<workItem from="1617117632667" duration="307000" />
<workItem from="1617160691713" duration="1016000" />
</task>
<servers />
</component>
@@ -117,18 +118,23 @@
<component name="XDebuggerManager">
<breakpoint-manager>
<breakpoints>
<line-breakpoint enabled="true" type="com.jetbrains.cidr.execution.debugger.OCBreakpointType">
<url>file://$PROJECT_DIR$/src/mesh/StreamAPI.cpp</url>
<line>20</line>
<option name="timeStamp" value="4" />
</line-breakpoint>
<line-breakpoint enabled="true" type="com.jetbrains.cidr.execution.debugger.OCBreakpointType">
<url>file://$PROJECT_DIR$/src/mesh/wifi/WiFiServerAPI.cpp</url>
<line>53</line>
<option name="timeStamp" value="6" />
</line-breakpoint>
<line-breakpoint enabled="true" type="com.jetbrains.cidr.execution.debugger.OCBreakpointType">
<url>file://$PROJECT_DIR$/src/mesh/wifi/WiFiServerAPI.cpp</url>
<line>37</line>
<option name="timeStamp" value="7" />
</line-breakpoint>
</breakpoints>
</breakpoint-manager>
<watches-manager>
<configuration name="CLion_Remote">
<watch expression="radioConfig" language="ObjectiveC" />
</configuration>
</watches-manager>
</component>
<component name="XSLT-Support.FileAssociations.UIState">
<expand />

View File

@@ -199,7 +199,7 @@ We'd love to have you join us on this merry little project. Please see our [deve
# Credits
This project is run by volunteers. Past contributors include:
This project is run by volunteers. We are a friendly group and welcome any contribution (code fixes, documentation, features, bug reports etc...). We try to be good about listing contributor names in release notes, but it has become unwieldy for the main-devs to keep updating the list below and we've neglected it too long. If you'd like your name included in this list please send a pull request to edit this README and simply add your line yourself. Thank you very much for your help!
- @astro-arphid: Added support for 433MHz radios in europe.
- @claesg: Various documentation fixes and 3D print enclosures

View File

@@ -1,3 +1,3 @@
set -e
pio run --environment native
gdbserver --once localhost:2345 .pio/build/native/program
gdbserver --once localhost:2345 .pio/build/native/program "$@"

View File

@@ -1,3 +1,3 @@
set -e
pio run --environment native
.pio/build/native/program
.pio/build/native/program "$@"

View File

@@ -4,8 +4,23 @@ You probably don't care about this section - skip to the next one.
## before next release
* DONE have android fill in if local GPS has poor signal
* fix heltec battery scaling
* DONE remote admin busted?
* DONE check android code - @havealoha comments about odd sleep behavior
* ABANDONED test github actions locally on linux
* DONE fix github actions per sasha tip
* tell ttgo to preinstall new bins
* DONE sendtext busted in portduino, due to bytetime calculations
* remove linux dependency in native build
* DONE tcp stream problem in python+pordtuino, server thinks client dropped when client DID NOT DROP
* DONE TCP mode for android, localhost is at 10.0.2.2
* make sure USB still works in android
* add portduino builds to zip
* add license to portduino and make announcement
* DONE naks are being dropped (though enqueuedLocal) sometimes before phone/PC gets them
* DONE have android fill in if local GPS has poor signal
* optionally restrict position sends to a named channel
* release to beta and amazon
* add reference counting to mesh packets
* allow multiple simultanteous phoneapi connections
* DONE split position.time and last_heard
@@ -37,6 +52,12 @@ You probably don't care about this section - skip to the next one.
## MQTT
* mqtt.meshtastic.org should have VERY basic auth at launch (to prevent abuse)
* use MQTT for simulator mesh network
* do initial development inside of portduino
* do as much possible on the device side (so we can eventually just have ESP32 talk directly to server)
* eventually add a MQTTPacket on the ToRadio & FromRadio links
## Multichannel support
* DONE cleanup the external notification and serial plugins
@@ -119,7 +140,7 @@ You probably don't care about this section - skip to the next one.
* DONE make all subpackets different versions of data
* DONE move routing control into a data packet
* have phoneapi done via plugin (will allow multiple simultaneous API clients - stop disabling BLE while using phone API)
* use reference counting and dynamic sizing for meshpackets.
* use reference counting and dynamic sizing for meshpackets. - use https://docs.microsoft.com/en-us/cpp/cpp/how-to-create-and-use-shared-ptr-instances?view=msvc-160 (already used in arduino)
* let multiple PhoneAPI endpoints work at once
* allow multiple simultaneous bluetooth connections (create the bluetooth phoneapi instance dynamically based on client id)
* DONE figure out how to add micro_delta to position, make it so that phone apps don't need to understand it?
@@ -137,6 +158,7 @@ You probably don't care about this section - skip to the next one.
For app cleanup:
* don't store redundant User admin or position broadcasts in the ToPhone queue (only keep one per sending node per proto type, and only most recent)
* use structured logging to kep logs in ram. Also send logs as packets to api clients
* DONE writeup nice python options docs (common cases, link to protobuf docs)
* have android app link to user manual

View File

@@ -0,0 +1,10 @@
# Running github actions locally
If you'd like to run the **same** integration tests we run on github but on your own machine, you can do the following.
1. Install homebrew per https://brew.sh/
2. Install https://github.com/nektos/act with "brew install act"
3. cd into meshtastic-device and run "act"
4. Select a "medium" sized image
5. Alas - this "act" build **almost** works, but fails because it can't find lib/nanopb/include/pb.h! So someone (you the reader? @geeksville ays hopefully...) needs to fix that before these instructions are complete.
6.

View File

@@ -40,7 +40,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 -Isrc/buzz -Wl,-Map,.pio/build/output.map
-Isrc -Isrc/mesh -Isrc/gps -Isrc/buzz -Wl,-Map,.pio/build/output.map
-DHW_VERSION_${sysenv.COUNTRY}
-DHW_VERSION=${sysenv.HW_VERSION}
-DUSE_THREAD_NAMES
@@ -68,7 +68,7 @@ lib_deps =
https://github.com/meshtastic/esp8266-oled-ssd1306.git#35d796226b853b0c0ff818b2f1aa3d35e7296a96 ; ESP8266_SSD1306
https://github.com/geeksville/OneButton.git ; OneButton library for non-blocking button debounce
1202 ; CRC32, explicitly needed because dependency is missing in the ble ota update lib
https://github.com/meshtastic/arduino-fsm.git#55c47b6cded91645aff05a27b6e5821d8d0f64be
https://github.com/meshtastic/arduino-fsm.git#829e967b8a95c094f73c60ef8dacfe66eae38940
https://github.com/meshtastic/SparkFun_Ublox_Arduino_Library.git#31015a55e630a2df77d9d714669c621a5bf355ad
https://github.com/meshtastic/RadioLib.git#07de964e929238949035fb0d5887026a3058df1a
https://github.com/meshtastic/TinyGPSPlus.git#f0f47067ef2f67c856475933188251c1ef615e79
@@ -110,7 +110,7 @@ lib_deps =
# board_build.ldscript = linker/esp32.extram.bss.ld
lib_ignore = segger_rtt
platform_packages =
framework-arduinoespressif32@https://github.com/meshtastic/arduino-esp32.git#352c8ea7cb73f10433ed139f34251979c470ad56
framework-arduinoespressif32@https://github.com/meshtastic/arduino-esp32.git#4cde0f5d412d2695184f32e8a47e9bea57b45276
; leave this commented out to avoid breaking Windows
upload_port = /dev/ttyUSB0

2
proto

Submodule proto updated: 0ea2328026...2aa1439214

View File

@@ -40,7 +40,7 @@ bool scheduleHWCallback(PendableFunction callback, void *param1, uint32_t param2
tParam1 = param1;
tParam2 = param2;
timerAlarmWrite(timer, delayMsec * 1000L, false); // Do not reload, we want it to be a single shot timer
timerAlarmWrite(timer, delayMsec * 1000UL, false); // Do not reload, we want it to be a single shot timer
timerRestart(timer);
timerAlarmEnable(timer);
return true;

View File

@@ -303,7 +303,9 @@ void PowerFSM_setup()
#ifndef NRF52_SERIES
// We never enter light-sleep or NB states on NRF52 (because the CPU uses so little power normally)
powerFSM.add_timed_transition(&stateDARK, &stateNB, getPref_phone_timeout_secs() * 1000, NULL, "Phone timeout");
// I don't think this transition is correct, turning off for now - @geeksville
// powerFSM.add_timed_transition(&stateDARK, &stateNB, getPref_phone_timeout_secs() * 1000, NULL, "Phone timeout");
powerFSM.add_timed_transition(&stateNB, &stateLS, getPref_min_wake_secs() * 1000, NULL, "Min wake timeout");
powerFSM.add_timed_transition(&stateDARK, &stateLS, getPref_wait_bluetooth_secs() * 1000, NULL, "Bluetooth timeout");
#else

View File

@@ -40,7 +40,7 @@ size_t RedirectablePrint::vprintf(const char *format, va_list arg)
va_end(arg);
return 0;
};
if (len >= printBufLen) {
if (len >= (int)printBufLen) {
delete[] printBuf;
printBufLen *= 2;
printBuf = new char[printBufLen];

View File

@@ -1,6 +1,5 @@
#pragma once
#include "configuration.h"
#include "../freertosinc.h"
namespace concurrency
@@ -28,4 +27,4 @@ class BinarySemaphorePosix
#endif
}
} // namespace concurrency

View File

@@ -1,5 +1,6 @@
#include "NotifiedWorkerThread.h"
#include "configuration.h"
#include "main.h"
#include <assert.h>
namespace concurrency
@@ -28,6 +29,7 @@ IRAM_ATTR bool NotifiedWorkerThread::notifyCommon(uint32_t v, bool overwrite)
if (overwrite || notification == 0) {
enabled = true;
setInterval(0); // Run ASAP
runASAP = true;
notification = v;
if (debugNotification)

View File

@@ -39,7 +39,7 @@ bool perhapsSetRTC(RTCQuality q, const struct timeval *tv)
currentQuality = q;
shouldSet = true;
DEBUG_MSG("Upgrading time to RTC %ld secs (quality %d)\n", tv->tv_sec, q);
} else if(q == RTCQualityGPS && (now - lastSetMsec) > (12 * 60 * 60 * 1000L)) {
} else if(q == RTCQualityGPS && (now - lastSetMsec) > (12 * 60 * 60 * 1000UL)) {
// Every 12 hrs we will slam in a new GPS time, to correct for local RTC clock drift
shouldSet = true;
DEBUG_MSG("Reapplying external time to correct clock drift %ld secs\n", tv->tv_sec);

View File

@@ -717,6 +717,7 @@ void Screen::handleSetOn(bool on)
dispdev.displayOn();
enabled = true;
setInterval(0); // Draw ASAP
runASAP = true;
} else {
DEBUG_MSG("Turning off screen\n");
dispdev.displayOff();
@@ -1053,6 +1054,7 @@ void Screen::setFastFramerate()
targetFramerate = SCREEN_TRANSITION_FRAMERATE;
ui.setTargetFPS(targetFramerate);
setInterval(0); // redraw ASAP
runASAP = true;
}
void DebugInfo::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y)

View File

@@ -317,7 +317,9 @@ void setup()
#endif
#ifdef DEBUG_PORT
consoleInit(); // Set serial baud rate and init our mesh console
if (!radioConfig.preferences.serial_disabled) {
consoleInit(); // Set serial baud rate and init our mesh console
}
#endif
initDeepSleep();
@@ -590,8 +592,14 @@ void rebootCheck()
}
}
// If a thread does something that might need for it to be rescheduled ASAP it can set this flag
// This will supress the current delay and instead try to run ASAP.
bool runASAP;
void loop()
{
runASAP = false;
// axpDebugOutput.loop();
// heap_caps_check_integrity_all(true); // FIXME - disable this expensive check
@@ -627,6 +635,7 @@ void loop()
mainController.nextThread->tillRun(millis())); */
// We want to sleep as long as possible here - because it saves power
mainDelay.delay(delayMsec);
if (!runASAP)
mainDelay.delay(delayMsec);
// if (didWake) DEBUG_MSG("wake!\n");
}

View File

@@ -22,4 +22,8 @@ const char *getDeviceName();
extern uint32_t rebootAtMsec;
// If a thread does something that might need for it to be rescheduled ASAP it can set this flag
// This will supress the current delay and instead try to run ASAP.
extern bool runASAP;
void nrf52Setup(), esp32Setup(), nrf52Loop(), esp32Loop();

View File

@@ -36,6 +36,7 @@ MeshPacket *MeshPlugin::allocAckNak(Routing_Error err, NodeNum to, PacketId idFr
Routing c = Routing_init_default;
c.error_reason = err;
c.which_variant = Routing_error_reason_tag;
// Now that we have moded sendAckNak up one level into the class heirarchy we can no longer assume we are a RoutingPlugin
// So we manually call pb_encode_to_bytes and specify routing port number

View File

@@ -15,7 +15,10 @@
#error ToRadio is too big
#endif
PhoneAPI::PhoneAPI() {}
PhoneAPI::PhoneAPI()
{
lastContactMsec = millis();
}
PhoneAPI::~PhoneAPI()
{
@@ -53,9 +56,12 @@ void PhoneAPI::close()
void PhoneAPI::checkConnectionTimeout()
{
if (isConnected()) {
bool newConnected = (millis() - lastContactMsec < getPref_phone_timeout_secs() * 1000L);
if (!newConnected)
uint32_t now = millis();
bool newContact = (now - lastContactMsec) < getPref_phone_timeout_secs() * 1000UL;
if (!newContact) {
DEBUG_MSG("Timed out on phone contact, dropping phone connection\n");
close();
}
}
}

View File

@@ -36,8 +36,6 @@ bool RF95Interface::init()
{
RadioLibInterface::init();
applyModemConfig();
if (power == 0)
power = POWER_DEFAULT;
@@ -86,24 +84,25 @@ void INTERRUPT_ATTR RF95Interface::disableInterrupt()
lora->clearDio0Action();
}
bool RF95Interface::reconfigure()
{
applyModemConfig();
RadioLibInterface::reconfigure();
// set mode to standby
setStandby();
// configure publicly accessible settings
int err = lora->setSpreadingFactor(sf);
if(err != ERR_NONE) recordCriticalError(CriticalErrorCode_InvalidRadioSetting);
if (err != ERR_NONE)
recordCriticalError(CriticalErrorCode_InvalidRadioSetting);
err = lora->setBandwidth(bw);
if(err != ERR_NONE) recordCriticalError(CriticalErrorCode_InvalidRadioSetting);
if (err != ERR_NONE)
recordCriticalError(CriticalErrorCode_InvalidRadioSetting);
err = lora->setCodingRate(cr);
if(err != ERR_NONE) recordCriticalError(CriticalErrorCode_InvalidRadioSetting);
if (err != ERR_NONE)
recordCriticalError(CriticalErrorCode_InvalidRadioSetting);
err = lora->setSyncWord(syncWord);
assert(err == ERR_NONE);
@@ -115,12 +114,14 @@ bool RF95Interface::reconfigure()
assert(err == ERR_NONE);
err = lora->setFrequency(freq);
if(err != ERR_NONE) recordCriticalError(CriticalErrorCode_InvalidRadioSetting);
if (err != ERR_NONE)
recordCriticalError(CriticalErrorCode_InvalidRadioSetting);
if (power > MAX_POWER) // This chip has lower power limits than some
power = MAX_POWER;
err = lora->setOutputPower(power);
if(err != ERR_NONE) recordCriticalError(CriticalErrorCode_InvalidRadioSetting);
if (err != ERR_NONE)
recordCriticalError(CriticalErrorCode_InvalidRadioSetting);
startReceive(); // restart receiving

View File

@@ -1,12 +1,12 @@
#include "configuration.h"
#include "RadioInterface.h"
#include "Channels.h"
#include "MeshRadio.h"
#include "MeshService.h"
#include "NodeDB.h"
#include "assert.h"
#include "Router.h"
#include "assert.h"
#include "configuration.h"
#include "sleep.h"
#include <assert.h>
#include <pb_decode.h>
@@ -31,8 +31,8 @@ const RegionInfo regions[] = {
/* Notes about the RU bandplan (from @denis-d in https://meshtastic.discourse.group/t/russian-band-plan-proposal/2786/2):
According to Annex 12 to GKRCh (National Radio Frequency Commission) decision № 18-46-03-1 (September 11th 2018) https://digital.gov.ru/uploaded/files/prilozhenie-12-k-reshenyu-gkrch-18-46-03-1.pdf 1
We have 3 options for 868 MHz:
According to Annex 12 to GKRCh (National Radio Frequency Commission) decision № 18-46-03-1 (September 11th 2018)
https://digital.gov.ru/uploaded/files/prilozhenie-12-k-reshenyu-gkrch-18-46-03-1.pdf 1 We have 3 options for 868 MHz:
864,0 - 865,0 MHz ERP 25mW, Duty Cycle 0.1% (3.6 sec in hour) or LBT (Listen Before Talk), prohibited in airports.
866,0 - 868,0 MHz ERP 25mW, Duty Cycle 1% or LBT, PSD (Power Spectrum Density) 1000mW/MHz, prohibited in airports
@@ -112,6 +112,8 @@ uint32_t RadioInterface::getPacketTime(MeshPacket *p)
/** The delay to use for retransmitting dropped packets */
uint32_t RadioInterface::getRetransmissionMsec(const MeshPacket *p)
{
assert(shortPacketMsec); // Better be non zero
// was 20 and 22 secs respectively, but now with shortPacketMsec as 2269, this should give the same range
return random(9 * shortPacketMsec, 10 * shortPacketMsec);
}
@@ -153,7 +155,7 @@ void printPacket(const char *prefix, const MeshPacket *p)
if (s.dest != 0)
DEBUG_MSG(" dest=%08x", s.dest);
if(s.request_id)
if (s.request_id)
DEBUG_MSG(" requestId=%0x", s.request_id);
/* now inside Data and therefore kinda opaque
@@ -185,6 +187,12 @@ RadioInterface::RadioInterface()
// DEBUG_MSG("Set meshradio defaults name=%s\n", channelSettings.name);
}
bool RadioInterface::reconfigure()
{
applyModemConfig();
return true;
}
bool RadioInterface::init()
{
DEBUG_MSG("Starting meshradio init...\n");
@@ -197,6 +205,8 @@ bool RadioInterface::init()
// radioIf.setThisAddress(nodeDB.getNodeNum()); // Note: we must do this here, because the nodenum isn't inited at constructor
// time.
applyModemConfig();
return true;
}
@@ -309,7 +319,7 @@ void RadioInterface::applyModemConfig()
// If user has manually specified a channel num, then use that, otherwise generate one by hashing the name
const char *channelName = channels.getName(channels.getPrimaryIndex());
int channel_num = channelSettings.channel_num ? channelSettings.channel_num - 1 : hash(channelName) % myRegion->numChannels;
freq = myRegion->freq + myRegion->spacing * channel_num;
freq = myRegion->freq + radioConfig.preferences.frequency_offset + myRegion->spacing * channel_num;
DEBUG_MSG("Set radio: name=%s, config=%u, ch=%d, power=%d\n", channelName, channelSettings.modem_config, channel_num, power);
DEBUG_MSG("Radio myRegion->freq: %f\n", myRegion->freq);

View File

@@ -104,7 +104,11 @@ class RadioInterface
virtual bool sleep() { return true; }
/// Disable this interface (while disabled, no packets can be sent or received)
void disable() { disabled = true; sleep(); }
void disable()
{
disabled = true;
sleep();
}
/**
* Send a packet (possibly by enquing in a private fifo). This routine will
@@ -126,7 +130,7 @@ class RadioInterface
/// Apply any radio provisioning changes
/// Make sure the Driver is properly configured before calling init().
/// \return true if initialisation succeeded.
virtual bool reconfigure() = 0;
virtual bool reconfigure();
/** The delay to use for retransmitting dropped packets */
uint32_t getRetransmissionMsec(const MeshPacket *p);
@@ -174,13 +178,6 @@ class RadioInterface
*/
void limitPower();
/**
* Convert our modemConfig enum into wf, sf, etc...
*
* These paramaters will be pull from the channelSettings global
*/
virtual void applyModemConfig();
/**
* Save the frequency we selected for later reuse.
*/
@@ -192,6 +189,13 @@ class RadioInterface
virtual void saveChannelNum(uint32_t savedChannelNum);
private:
/**
* Convert our modemConfig enum into wf, sf, etc...
*
* These paramaters will be pull from the channelSettings global
*/
void applyModemConfig();
/// Return 0 if sleep is okay
int preflightSleepCb(void *unused = NULL) { return canSleep() ? 0 : 1; }
@@ -208,18 +212,6 @@ class SimRadio : public RadioInterface
{
public:
virtual ErrorCode send(MeshPacket *p);
// methods from radiohead
/// Initialise the Driver transport hardware and software.
/// Make sure the Driver is properly configured before calling init().
/// \return true if initialisation succeeded.
virtual bool init() { return true; }
/// Apply any radio provisioning changes
/// Make sure the Driver is properly configured before calling init().
/// \return true if initialisation succeeded.
virtual bool reconfigure() { return true; }
};
/// Debug printing for packets

View File

@@ -79,9 +79,10 @@ class ReliableRouter : public FloodingRouter
/** Do our retransmission handling */
virtual int32_t runOnce()
{
auto d = FloodingRouter::runOnce();
// Note: We must doRetransmissions FIRST, because it might queue up work for the base class runOnce implementation
auto d = doRetransmissions();
int32_t r = doRetransmissions();
int32_t r = FloodingRouter::runOnce();
return min(d, r);
}
@@ -109,7 +110,6 @@ class ReliableRouter : public FloodingRouter
PendingPacket *startRetransmission(MeshPacket *p);
private:
/**
* Stop any retransmissions we are doing of the specified node/packet ID pair
*

View File

@@ -4,6 +4,7 @@
#include "NodeDB.h"
#include "RTC.h"
#include "configuration.h"
#include "main.h"
#include "mesh-pb-constants.h"
#include "plugins/RoutingPlugin.h"
@@ -55,9 +56,11 @@ int32_t Router::runOnce()
{
MeshPacket *mp;
while ((mp = fromRadioQueue.dequeuePtr(0)) != NULL) {
// printPacket("handle fromRadioQ", mp);
perhapsHandleReceived(mp);
}
// DEBUG_MSG("sleeping forever!\n");
return INT32_MAX; // Wait a long time - until we get woken for the message queue
}
@@ -117,7 +120,9 @@ void Router::abortSendAndNak(Routing_Error err, MeshPacket *p)
void Router::setReceivedMessage()
{
// DEBUG_MSG("set interval to ASAP\n");
setInterval(0); // Run ASAP, so we can figure out our correct sleep time
runASAP = true;
}
ErrorCode Router::sendLocal(MeshPacket *p)

View File

@@ -23,8 +23,6 @@ bool SX1262Interface::init()
pinMode(SX1262_POWER_EN, OUTPUT);
#endif
RadioLibInterface::init();
#ifdef SX1262_RXEN // set not rx or tx mode
digitalWrite(SX1262_RXEN, LOW); // Set low before becoming an output
pinMode(SX1262_RXEN, OUTPUT);
@@ -38,11 +36,11 @@ bool SX1262Interface::init()
float tcxoVoltage = 0; // None - we use an XTAL
#else
// Use DIO3 to power tcxo per https://github.com/jgromes/RadioLib/issues/12#issuecomment-520695575
float tcxoVoltage = 1.8;
float tcxoVoltage = 1.8;
#endif
bool useRegulatorLDO = false; // Seems to depend on the connection to pin 9/DCC_SW - if an inductor DCDC?
applyModemConfig();
RadioLibInterface::init();
if (power == 0)
power = SX1262_MAX_POWER;
@@ -72,20 +70,23 @@ bool SX1262Interface::init()
bool SX1262Interface::reconfigure()
{
applyModemConfig();
RadioLibInterface::reconfigure();
// set mode to standby
setStandby();
// configure publicly accessible settings
int err = lora.setSpreadingFactor(sf);
if(err != ERR_NONE) recordCriticalError(CriticalErrorCode_InvalidRadioSetting);
if (err != ERR_NONE)
recordCriticalError(CriticalErrorCode_InvalidRadioSetting);
err = lora.setBandwidth(bw);
if(err != ERR_NONE) recordCriticalError(CriticalErrorCode_InvalidRadioSetting);
if (err != ERR_NONE)
recordCriticalError(CriticalErrorCode_InvalidRadioSetting);
err = lora.setCodingRate(cr);
if(err != ERR_NONE) recordCriticalError(CriticalErrorCode_InvalidRadioSetting);
if (err != ERR_NONE)
recordCriticalError(CriticalErrorCode_InvalidRadioSetting);
// Hmm - seems to lower SNR when the signal levels are high. Leaving off for now...
err = lora.setRxGain(true);
@@ -101,7 +102,8 @@ bool SX1262Interface::reconfigure()
assert(err == ERR_NONE);
err = lora.setFrequency(freq);
if(err != ERR_NONE) recordCriticalError(CriticalErrorCode_InvalidRadioSetting);
if (err != ERR_NONE)
recordCriticalError(CriticalErrorCode_InvalidRadioSetting);
if (power > 22) // This chip has lower power limits than some
power = 22;

View File

@@ -79,7 +79,7 @@ extern const pb_msgdesc_t AdminMessage_msg;
#define AdminMessage_fields &AdminMessage_msg
/* Maximum encoded size of messages (where known) */
#define AdminMessage_size 351
#define AdminMessage_size 360
#ifdef __cplusplus
} /* extern "C" */

View File

@@ -85,6 +85,8 @@ typedef struct _RadioConfig_UserPreferences {
bool is_router;
bool is_low_power;
bool fixed_position;
bool serial_disabled;
float frequency_offset;
bool factory_reset;
bool debug_log_enabled;
pb_size_t ignore_incoming_count;
@@ -150,9 +152,9 @@ extern "C" {
/* Initializer values for message structs */
#define RadioConfig_init_default {false, RadioConfig_UserPreferences_init_default}
#define RadioConfig_UserPreferences_init_default {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, "", "", 0, _RegionCode_MIN, _ChargeCurrent_MIN, _LocationSharing_MIN, _GpsOperation_MIN, 0, 0, 0, 0, 0, 0, 0, 0, {0, 0, 0}, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, _RadioConfig_UserPreferences_EnvironmentalMeasurementSensorType_MIN, 0, 0}
#define RadioConfig_UserPreferences_init_default {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, "", "", 0, _RegionCode_MIN, _ChargeCurrent_MIN, _LocationSharing_MIN, _GpsOperation_MIN, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, {0, 0, 0}, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, _RadioConfig_UserPreferences_EnvironmentalMeasurementSensorType_MIN, 0, 0}
#define RadioConfig_init_zero {false, RadioConfig_UserPreferences_init_zero}
#define RadioConfig_UserPreferences_init_zero {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, "", "", 0, _RegionCode_MIN, _ChargeCurrent_MIN, _LocationSharing_MIN, _GpsOperation_MIN, 0, 0, 0, 0, 0, 0, 0, 0, {0, 0, 0}, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, _RadioConfig_UserPreferences_EnvironmentalMeasurementSensorType_MIN, 0, 0}
#define RadioConfig_UserPreferences_init_zero {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, "", "", 0, _RegionCode_MIN, _ChargeCurrent_MIN, _LocationSharing_MIN, _GpsOperation_MIN, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, {0, 0, 0}, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, _RadioConfig_UserPreferences_EnvironmentalMeasurementSensorType_MIN, 0, 0}
/* Field tags (for use in manual encoding/decoding) */
#define RadioConfig_UserPreferences_position_broadcast_secs_tag 1
@@ -177,6 +179,8 @@ extern "C" {
#define RadioConfig_UserPreferences_is_router_tag 37
#define RadioConfig_UserPreferences_is_low_power_tag 38
#define RadioConfig_UserPreferences_fixed_position_tag 39
#define RadioConfig_UserPreferences_serial_disabled_tag 40
#define RadioConfig_UserPreferences_frequency_offset_tag 41
#define RadioConfig_UserPreferences_factory_reset_tag 100
#define RadioConfig_UserPreferences_debug_log_enabled_tag 101
#define RadioConfig_UserPreferences_ignore_incoming_tag 103
@@ -237,6 +241,8 @@ X(a, STATIC, SINGULAR, UINT32, gps_attempt_time, 36) \
X(a, STATIC, SINGULAR, BOOL, is_router, 37) \
X(a, STATIC, SINGULAR, BOOL, is_low_power, 38) \
X(a, STATIC, SINGULAR, BOOL, fixed_position, 39) \
X(a, STATIC, SINGULAR, BOOL, serial_disabled, 40) \
X(a, STATIC, SINGULAR, FLOAT, frequency_offset, 41) \
X(a, STATIC, SINGULAR, BOOL, factory_reset, 100) \
X(a, STATIC, SINGULAR, BOOL, debug_log_enabled, 101) \
X(a, STATIC, REPEATED, UINT32, ignore_incoming, 103) \
@@ -276,8 +282,8 @@ extern const pb_msgdesc_t RadioConfig_UserPreferences_msg;
#define RadioConfig_UserPreferences_fields &RadioConfig_UserPreferences_msg
/* Maximum encoded size of messages (where known) */
#define RadioConfig_size 348
#define RadioConfig_UserPreferences_size 345
#define RadioConfig_size 357
#define RadioConfig_UserPreferences_size 354
#ifdef __cplusplus
} /* extern "C" */

View File

@@ -11,7 +11,6 @@
#include <HTTPBodyParser.hpp>
#include <HTTPMultipartBodyParser.hpp>
#include <HTTPURLEncodedBodyParser.hpp>
#include <Preferences.h>
#include <SPIFFS.h>
#ifndef NO_ESP32
@@ -837,11 +836,6 @@ void handleReport(HTTPRequest *req, HTTPResponse *res)
ResourceParameters *params = req->getParams();
std::string content;
Preferences preferences;
preferences.begin("meshtastic", false);
uint32_t rebootCounter = preferences.getUInt("rebootCounter", 0);
if (!params->getQueryParameter("content", content)) {
content = "json";
}

View File

@@ -1,76 +1,61 @@
#include "CryptoEngine.h"
#include "target_specific.h"
#include "PortduinoGPIO.h"
#include "mesh/RF95Interface.h"
#include "sleep.h"
#include "target_specific.h"
#include <Utility.h>
#include <assert.h>
// FIXME - move getMacAddr/setBluetoothEnable into a HALPlatform class
uint32_t hwId; // fixme move into portduino
void getMacAddr(uint8_t *dmac)
{
if (!hwId) {
notImplemented("getMacAddr");
hwId = random();
}
dmac[0] = 0x80;
dmac[1] = 0;
dmac[2] = 0;
dmac[3] = hwId >> 16;
dmac[4] = hwId >> 8;
dmac[5] = hwId & 0xff;
}
// FIXME - move setBluetoothEnable into a HALPlatform class
void setBluetoothEnable(bool on)
{
// not needed
}
void cpuDeepSleep(uint64_t msecs) {
void cpuDeepSleep(uint64_t msecs)
{
notImplemented("cpuDeepSleep");
}
void updateBatteryLevel(uint8_t level) NOT_IMPLEMENTED("updateBatteryLevel");
/** Dear pinetab hardware geeks!
*
*
* The current pinetab lora module has a slight bug. The ch341 part only provides ISR assertions on edges.
* This makes sense because USB interrupts happen through fast/repeated special irq urbs that are constantly
* chattering on the USB bus.
*
*
* But this isn't sufficient for level triggered ISR sources like the sx127x radios. The common way that seems to
* be addressed by cs341 users is to **always** connect the INT# (pin 26 on the ch341f) signal to one of the GPIO signals
* on the part. I'd recommend connecting that LORA_DIO0/INT# line to pin 19 (data 4) on the pinetab board. This would
* provide an efficent mechanism so that the (kernel) code in the cs341 driver that I've slightly hacked up to see the
* current state of LORA_DIO0. Without that access, I can't know if the interrupt is still pending - which would create
* race conditions in packet handling.
*
* race conditions in packet handling.
*
* My workaround is to poll the status register internally to the sx127x. Which is expensive because it involves a number of
* i2c transactions and many trips back and forth between kernel and my userspace app. I think shipping the current version
* of the pinetab lora device would be fine because I can poll slowly (because lora is slow). But if you ever have cause to
* rev this board. I highly encourage this small change.
*
*
* Btw - your little "USB lora dongle" is really neat. I encourage you to sell it, because even non pinetab customers could
* use it to easily add lora to rasberry pi, desktop pcs etc...
*
*
* Porduino helper class to do this i2c based polling:
*/
class R595PolledIrqPin : public GPIOPin {
public:
class R595PolledIrqPin : public GPIOPin
{
public:
R595PolledIrqPin() : GPIOPin(LORA_DIO0, "LORA_DIO0") {}
/// Read the low level hardware for this pin
virtual PinStatus readPinHardware()
{
if(isrPinStatus < 0)
if (isrPinStatus < 0)
return LOW; // No interrupt handler attached, don't bother polling i2c right now
else {
extern RadioInterface *rIf; // FIXME, temporary hack until we know if we need to keep this
extern RadioInterface *rIf; // FIXME, temporary hack until we know if we need to keep this
assert(rIf);
RF95Interface *rIf95 = static_cast<RF95Interface *>(rIf);
@@ -81,17 +66,17 @@ public:
}
};
/** apps run under portduino can optionally define a portduinoSetup() to
/** apps run under portduino can optionally define a portduinoSetup() to
* use portduino specific init code (such as gpioBind) to setup portduino on their host machine,
* before running 'arduino' code.
*/
void portduinoSetup() {
printf("Setting up Meshtastic on Porduino...\n");
void portduinoSetup()
{
printf("Setting up Meshtastic on Porduino...\n");
// FIXME: disable while not testing with real hardware
// gpioBind(new R595PolledIrqPin());
// FIXME: disable while not testing with real hardware
// gpioBind(new R595PolledIrqPin());
// gpioBind((new SimGPIOPin(LORA_RESET, "LORA_RESET")));
// gpioBind((new SimGPIOPin(RF95_NSS, "RF95_NSS"))->setSilent());
// gpioBind((new SimGPIOPin(LORA_RESET, "LORA_RESET")));
// gpioBind((new SimGPIOPin(RF95_NSS, "RF95_NSS"))->setSilent());
}

View File

@@ -1,4 +1,4 @@
[VERSION]
major = 1
minor = 2
build = 16
build = 20