Compare commits

...

61 Commits

Author SHA1 Message Date
Ben Meadors
f06c56a51b Removing release build type due to huge amount of flash utilization 2024-05-10 07:14:28 -05:00
Ben Meadors
ac22a503de Revert "Revert "Add Sensirion SHT4X sensors (#3792)" (#3845)" (#3850)
This reverts commit 5d9800b7c2.
2024-05-10 07:13:12 -05:00
Jonathan Bennett
676319a9ca Implement chunked SPI transfer for ch341 (#3847)
This seems to fix the ch341 quirk where large packets fail to send. As it can be problematic for other radios, we gate it behind "ch341_quirk" in the config.
2024-05-10 04:36:20 -05:00
Ben Meadors
5d9800b7c2 Revert "Add Sensirion SHT4X sensors (#3792)" (#3845)
This reverts commit 5371f134ba.
2024-05-09 21:25:36 -05:00
Jonathan Bennett
0c89aff0f6 Enable telemetry and power telemetry on the native target 2024-05-09 15:45:16 -05:00
todd-herbert
5e160b21c7 T-Echo screen and button performance (#3840)
* Make button timing configurable per variant

* Adjust button timing for T-Echo
Easier multi-clicks for features like "toggle backlight" (4x click)

* Fewer full-refreshes for T-Echo display
Disables ghost pixel tracking: T-Echo ghost pixels are fairly faint.
2024-05-09 08:14:58 -05:00
todd-herbert
75dc8cccec Button ISR runs thread asap (#3801) 2024-05-08 16:08:24 -05:00
Nicholas Baddorf
147de75a02 Added modifier key combination to allow keyboard shortcuts on t-deck (#3668)
* Updated kbI2cBase.cpp

Updated keyboard settings for t-deck to allow a modifier key to trigger 'tab', mute notifications, or quit. To trigger the modifier press the shift key and mic (0) button at the same time. Then press q (quit), m (mute), or t (tab).

* Update kbI2cBase.cpp

* fixed formatting issues in kbI2cBase.cpp

* Removed keyboard shortcut code that doesnt work

alt+t does not work on a t-deck so I removed it to avoid confusion.

* Updated kbI2cBase.cpp

Updated keyboard settings for t-deck to allow a modifier key to trigger 'tab', mute notifications, or quit. To trigger the modifier press the shift key and mic (0) button at the same time. Then press q (quit), m (mute), or t (tab).

* Update kbI2cBase.cpp

* fixed formatting issues in kbI2cBase.cpp

* Removed keyboard shortcut code that doesnt work

alt+t does not work on a t-deck so I removed it to avoid confusion.

* Changed modifier key to alt+c

* Added screen brightness functionality

Use modifier key with o(+) to increase brightness or i(-) to decrease.

Currently there are 4 levels of brightness, (L, ML, MH, H). I would like to add a popup message to tell you the brightness.

* Added checks to disable screen brightness changes on unsupported hardware

* Setting the brightness code to work on only applicable devices

* Added "function symbol" display to bottom right corner of screen. Now shows when mute is active or modifier key is pressed. Also fixed some other minor issues.

* commented out a log

* Reworked how modifier functions worked, added

I wasn’t  happy with my previous implementation, and I think it would have caused issues with other devices. This should work on all devices.

* Added back the function I moved causing issue with versions

* Fixed the version conflicts, everything seems to work fine now

---------

Co-authored-by: Ben Meadors <benmmeadors@gmail.com>
Co-authored-by: Thomas Göttgens <tgoettgens@gmail.com>
2024-05-08 07:37:50 -05:00
pr000t
5371f134ba Add Sensirion SHT4X sensors (#3792)
* add Sensirion SHT4X sensors

* Update platformio.ini

Fix lib version

* Delete src/mesh/generated/meshtastic/telemetry.pb.h

* Revert "Delete src/mesh/generated/meshtastic/telemetry.pb.h"

This reverts commit 8e5e6a9f6ff4e31ed32775741c03a855e663a5de.

* remove modification on generated file

* Update ScanI2CTwoWire.cpp

Fix copy/paste issue

---------

Co-authored-by: Thomas Göttgens <tgoettgens@gmail.com>
2024-05-08 07:02:53 -05:00
Max
8105c0440a New variants PROMICRO_DIY (#3788)
* New variants PROMICRO_DIY

* Renaming and cleanup

* Renaming - phase 2

* nrf52_promicro: Trunk formatting

---------

Co-authored-by: Ben Meadors <benmmeadors@gmail.com>
2024-05-08 06:53:13 -05:00
Ben Meadors
cbf20e4cee Default to new vendor ntp pool (#3819) 2024-05-07 07:57:30 -05:00
Jonathan Bennett
c009c0db1e Elimate non-text output for Portduino 2024-05-06 22:27:12 -05:00
Ben Meadors
2c99f11073 Revert "set USB_CDC_ON_BOOT, udate arduinoespressif32 to 2.0.15 (#3764)" (#3809)
This reverts commit 71400103b3.
2024-05-06 17:35:38 -05:00
Ben Meadors
0d57d29cbd Send fixed position to mesh after setting it (#3803) 2024-05-06 14:51:19 -05:00
Thomas Göttgens
353c7e07d1 Wiphone (#3793)
* add wiphone, still WIP

* (very preliminary) wiphone support

* undo config changes

* revert extensions.json

* eh?
2024-05-06 06:48:57 -05:00
HarukiToreda
77a66e1dce Fix for EnvironmentTelemetry Screen (#3785)
* Update EnvironmentTelemetry.cpp

* Update EnvironmentTelemetry.cpp

Corrected lines I deleted by mistake

* trunk fmt

---------

Co-authored-by: Thomas Göttgens <tgoettgens@gmail.com>
2024-05-06 06:47:34 -05:00
Thomas Göttgens
e98c3bf5d0 Merge pull request #3802 from meshtastic/create-pull-request/patch
Changes by create-pull-request action
2024-05-06 13:39:44 +02:00
caveman99
5e9d48d0d7 [create-pull-request] automated change 2024-05-06 11:37:03 +00:00
Thomas Göttgens
8e91f895a6 Merge pull request #3800 from oseiler2/fix/RCWL9620-MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
Add MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR exclusion to RCWL9620
2024-05-06 12:06:17 +02:00
Oliver Seiler
b155a5b6dc rearrange includes 2024-05-06 12:15:49 +12:00
Oliver Seiler
2c30923e3e add MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR exclusion to RCWL9620 2024-05-06 11:25:18 +12:00
Thomas Göttgens
0afe2d459f Merge pull request #3790 from meshtastic/create-pull-request/patch
Changes by create-pull-request action
2024-05-05 17:34:07 +02:00
caveman99
0b239e618d [create-pull-request] automated change 2024-05-05 15:32:28 +00:00
Thomas Göttgens
e9ebdfeff2 Merge pull request #3787 from GUVWAF/ccToPhoneErr
Check if packet is not released before CC to phone
2024-05-05 16:47:11 +02:00
GUVWAF
6fb7d7f2d7 Check if packet is not released before CC to phone 2024-05-05 13:49:50 +02:00
tuxphone
70712d859c Enable compiling with gccnoneeabi 12.3.1 for nRF52 targets, additional small fixes (#3778)
* Fix type of nodeNum

Type of nodeNum is NodeNum, not uint

* typo

fixed typo "resumeAdverising()"

* fix missing #include "time.h"

Missing include breaks compilation with gccnoneeabi 12.3.1 for nrf52 targets on windows hosts.

* change type uint to unsigned int

uint is not a standard type. Using uint breaks compilation with gccnoneeabi 12.3.1 for nRF52 targets on windows hosts.

* fix type of channel_num

Type of channel_num should be uint32_t (as this is the type of hash() and numChannels).

Using uint non-standard type uint breaks compilation with gccnoneeabi 12.3.1 for nRF52 targets on windows hosts.

* Update nrf52.ini

Default build type should be "release" as this is the default of platformio.

* Update GPS.cpp

uint to unsigned int
2024-05-03 15:49:22 -05:00
Thomas Göttgens
4d9081b3b1 Merge pull request #3678 from meshtastic/RCWL-9620
Support radar sensor RCWL-9620 on i2c
2024-05-03 20:37:27 +02:00
Thomas Göttgens
7643a1acb1 Merge branch 'RCWL-9620' of github.com:meshtastic/firmware into RCWL-9620 2024-05-03 20:05:24 +02:00
Thomas Göttgens
61216e579e there 2024-05-03 19:25:37 +02:00
Thomas Göttgens
e31bb2d513 Merge branch 'master' into RCWL-9620 2024-05-03 16:00:08 +02:00
Thomas Göttgens
a8c38c4580 Merge pull request #3775 from lewisxhe/master
Fix the infinite restart caused by unformatted t-echo fs file system
2024-05-03 15:59:07 +02:00
Thomas Göttgens
85e0372d26 darn you, trunk. foiled my cunning plan. 2024-05-03 15:58:16 +02:00
Thomas Göttgens
53bd9de9b8 Merge branch 'master' into RCWL-9620 2024-05-03 15:12:51 +02:00
Thomas Göttgens
13ad524538 make clang-format happy again. Also fix assorted variable shrouding and logic bleeps 2024-05-03 15:10:57 +02:00
Thomas Göttgens
5f90f45ac4 trunk fmt 2024-05-03 15:04:11 +02:00
lewisxhe
dc0593c5a7 Fix the infinite restart caused by unformatted t-echo fs file system 2024-05-03 15:04:11 +02:00
Thomas Göttgens
df3cceb108 Merge pull request #3776 from oseiler2/fix/MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
Fix #MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
2024-05-03 15:02:47 +02:00
Thomas Göttgens
827dcfca4a trunk fmt 2024-05-03 14:26:57 +02:00
Thomas Göttgens
9fb6148aff Merge branch 'master' into RCWL-9620 2024-05-03 12:28:08 +02:00
Oliver Seiler
6c1377aa39 fix case statement 2024-05-03 18:59:33 +12:00
Oliver Seiler
077ca5919a MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR refinements 2024-05-03 14:15:13 +12:00
Oliver Seiler
668b716119 move QMC5883LCompass dependency to environmental_base 2024-05-03 14:15:13 +12:00
Oliver Seiler
eaa7e21bc7 exclude AccelerometerThread when MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR is set 2024-05-03 14:15:13 +12:00
Oliver Seiler
be0e882be1 exclude sensors when MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR set 2024-05-03 14:15:13 +12:00
github-actions[bot]
09080d76ad [create-pull-request] automated change (#3773)
Co-authored-by: thebentern <thebentern@users.noreply.github.com>
2024-05-02 20:46:22 -05:00
Ben Meadors
472db5b237 Merge branch 'master' into RCWL-9620 2024-04-28 07:05:54 -05:00
Ben Meadors
1c0227f90c Merge branch 'master' into RCWL-9620 2024-04-23 14:19:08 -05:00
Thomas Göttgens
c6e940af81 Merge branch 'master' into RCWL-9620 2024-04-23 14:04:22 +02:00
Ben Meadors
048f0a1601 Merge branch 'master' into RCWL-9620 2024-04-21 14:41:49 -05:00
Ben Meadors
675d8fe089 Merge branch 'master' into RCWL-9620 2024-04-21 12:37:38 -05:00
Thomas Göttgens
952393ca0f Merge branch 'master' into RCWL-9620 2024-04-21 18:34:40 +02:00
Thomas Göttgens
a231cd2ad0 derp... 2024-04-21 16:35:41 +02:00
Thomas Göttgens
a957065fe8 Merge branch 'master' into RCWL-9620 2024-04-21 14:47:29 +02:00
Thomas Göttgens
402b0d7e0b ditch that no-good m5 dependancy and do it ourself 2024-04-21 14:39:55 +02:00
Thomas Göttgens
13ebda6b2f Merge branch 'RCWL-9620' of github.com:meshtastic/firmware into RCWL-9620 2024-04-21 14:35:32 +02:00
Ben Meadors
1dd19cec6e Merge branch 'master' into RCWL-9620 2024-04-21 07:34:11 -05:00
Thomas Göttgens
1f9c295c9e Merge branch 'RCWL-9620' of github.com:meshtastic/firmware into RCWL-9620 2024-04-21 13:48:08 +02:00
Thomas Göttgens
5218aaafcf Change name 2024-04-21 11:41:52 +02:00
Thomas Göttgens
c480f0870c Support radar sensor RCWL-9620 on i2c 2024-04-21 11:41:52 +02:00
Thomas Göttgens
94e1f016e5 Change name 2024-04-20 20:49:57 +02:00
Thomas Göttgens
9170fe0580 Support radar sensor RCWL-9620 on i2c 2024-04-20 20:30:22 +02:00
100 changed files with 1555 additions and 238 deletions

View File

@@ -3,7 +3,7 @@
platform = platformio/nordicnrf52@^10.4.0
extends = arduino_base
build_type = debug ; I'm debugging with ICE a lot now
build_type = debug
build_flags =
${arduino_base.build_flags}
-DSERIAL_BUFFER_SIZE=1024

View File

@@ -52,6 +52,8 @@ Lora:
# TXen: x # TX and RX enable pins
# RXen: x
# ch341_quirk: true # Uncomment this to use the chunked SPI transfer that seems to fix the ch341
### Set gpio chip to use in /dev/. Defaults to 0.
### Notably the Raspberry Pi 5 puts the GPIO header on gpiochip4
# gpiochip: 4

View File

@@ -0,0 +1,52 @@
{
"build": {
"arduino": {
"ldscript": "nrf52840_s140_v6.ld"
},
"core": "nRF5",
"cpu": "cortex-m4",
"extra_flags": "-DARDUINO_NRF52840_FEATHER -DNRF52840_XXAA",
"f_cpu": "64000000L",
"hwids": [
["0x239A", "0x00B3"],
["0x239A", "0x8029"],
["0x239A", "0x0029"],
["0x239A", "0x002A"],
["0x239A", "0x802A"]
],
"usb_product": "ProMicro compatible nRF52840",
"mcu": "nrf52840",
"variant": "promicro_diy",
"bsp": {
"name": "adafruit"
},
"softdevice": {
"sd_flags": "-DS140",
"sd_name": "s140",
"sd_version": "6.1.1",
"sd_fwid": "0x00B6"
},
"bootloader": {
"settings_addr": "0xFF000"
}
},
"connectivity": ["bluetooth"],
"debug": {
"jlink_device": "nRF52840_xxAA",
"svd_path": "nrf52840.svd"
},
"frameworks": ["arduino"],
"name": "ProMicro compatible nRF52840",
"upload": {
"maximum_ram_size": 248832,
"maximum_size": 815104,
"speed": 115200,
"protocol": "nrfutil",
"protocols": ["nrfutil", "jlink", "nrfjprog", "stlink"],
"use_1200bps_touch": true,
"require_upload_port": true,
"wait_for_upload_port": true
},
"url": "https://www.nologo.tech/product/otherboard/NRF52840.html",
"vendor": "Nologo"
}

View File

@@ -7,7 +7,6 @@
"extra_flags": [
"-DBOARD_HAS_PSRAM",
"-DLILYGO_TBEAM_S3_CORE",
"-DARDUINO_USB_CDC_ON_BOOT=1",
"-DARDUINO_USB_MODE=1",
"-DARDUINO_RUNNING_CORE=1",
"-DARDUINO_EVENT_RUNNING_CORE=1"

34
boards/wiphone.json Normal file
View File

@@ -0,0 +1,34 @@
{
"build": {
"arduino": {
"ldscript": "esp32_out.ld",
"partitions": "default_16MB.csv"
},
"core": "esp32",
"extra_flags": [
"-DARDUINO_WIPHONE14",
"-DBOARD_HAS_PSRAM",
"-mfix-esp32-psram-cache-issue",
"-mfix-esp32-psram-cache-strategy=memw"
],
"f_cpu": "240000000L",
"f_flash": "40000000L",
"flash_mode": "dio",
"mcu": "esp32",
"variant": "wiphone",
"board": "WiPhone"
},
"connectivity": ["wifi", "bluetooth"],
"frameworks": ["arduino", "espidf"],
"name": "WIPhone Integrated 1.4",
"upload": {
"flash_size": "16MB",
"maximum_ram_size": 532480,
"maximum_size": 6553600,
"maximum_data_size": 4521984,
"require_upload_port": true,
"speed": 921600
},
"url": "https://www.wiphone.io/",
"vendor": "HackEDA"
}

View File

@@ -96,7 +96,6 @@ check_flags =
framework = arduino
lib_deps =
${env.lib_deps}
mprograms/QMC5883LCompass@^1.2.0
end2endzone/NonBlockingRTTTL@^1.3.0
https://github.com/meshtastic/SparkFun_ATECCX08a_Arduino_Library.git#5cf62b36c6f30bc72a07bdb2c11fc9a22d1e31da
@@ -132,4 +131,6 @@ lib_deps =
adafruit/Adafruit MPU6050@^2.2.4
adafruit/Adafruit LIS3DH@^1.2.4
https://github.com/lewisxhe/SensorLib#27fd0f721e20cd09e1f81383f0ba58a54fe84a17
adafruit/Adafruit LSM6DS@^4.7.2
adafruit/Adafruit LSM6DS@^4.7.2
mprograms/QMC5883LCompass@^1.2.0
https://github.com/Sensirion/arduino-i2c-sht4x#1.1.0

View File

@@ -1,6 +1,9 @@
#include "configuration.h"
#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
#include "PowerFSM.h"
#include "concurrency/OSThread.h"
#include "configuration.h"
#include "main.h"
#include "power.h"
@@ -172,4 +175,6 @@ class AccelerometerThread : public concurrency::OSThread
Adafruit_LSM6DS3TRC lsm;
};
} // namespace concurrency
} // namespace concurrency
#endif

View File

@@ -52,8 +52,8 @@ ButtonThread::ButtonThread() : OSThread("Button")
#if defined(BUTTON_PIN) || defined(ARCH_PORTDUINO)
userButton.attachClick(userButtonPressed);
userButton.setClickMs(250);
userButton.setPressMs(c_longPressTime);
userButton.setClickMs(BUTTON_CLICK_MS);
userButton.setPressMs(BUTTON_LONGPRESS_MS);
userButton.setDebounceMs(1);
userButton.attachDoubleClick(userButtonDoublePressed);
userButton.attachMultiClick(userButtonMultiPressed, this); // Reference to instance: get click count from non-static OneButton
@@ -70,8 +70,8 @@ ButtonThread::ButtonThread() : OSThread("Button")
pinMode(BUTTON_PIN_ALT, INPUT_PULLUP_SENSE);
#endif
userButtonAlt.attachClick(userButtonPressed);
userButtonAlt.setClickMs(250);
userButtonAlt.setPressMs(c_longPressTime);
userButtonAlt.setClickMs(BUTTON_CLICK_MS);
userButtonAlt.setPressMs(BUTTON_LONGPRESS_MS);
userButtonAlt.setDebounceMs(1);
userButtonAlt.attachDoubleClick(userButtonDoublePressed);
userButtonAlt.attachLongPressStart(userButtonPressedLongStart);
@@ -80,7 +80,7 @@ ButtonThread::ButtonThread() : OSThread("Button")
#ifdef BUTTON_PIN_TOUCH
userButtonTouch = OneButton(BUTTON_PIN_TOUCH, true, true);
userButtonTouch.setPressMs(400);
userButtonTouch.setPressMs(BUTTON_TOUCH_MS);
userButtonTouch.attachLongPressStart(touchPressedLongStart); // Better handling with longpress than click?
#endif
@@ -214,6 +214,7 @@ int32_t ButtonThread::runOnce()
btnEvent = BUTTON_EVENT_NONE;
}
runASAP = false;
return 50;
}
@@ -234,6 +235,7 @@ void ButtonThread::attachButtonInterrupts()
BaseType_t higherWake = 0;
mainDelay.interruptFromISR(&higherWake);
ButtonThread::userButton.tick();
runASAP = true;
},
CHANGE);
#endif
@@ -280,6 +282,7 @@ void ButtonThread::wakeOnIrq(int irq, int mode)
[] {
BaseType_t higherWake = 0;
mainDelay.interruptFromISR(&higherWake);
runASAP = true;
},
FALLING);
}

View File

@@ -4,11 +4,22 @@
#include "concurrency/OSThread.h"
#include "configuration.h"
#ifndef BUTTON_CLICK_MS
#define BUTTON_CLICK_MS 250
#endif
#ifndef BUTTON_LONGPRESS_MS
#define BUTTON_LONGPRESS_MS 5000
#endif
#ifndef BUTTON_TOUCH_MS
#define BUTTON_TOCH_MS 400
#endif
class ButtonThread : public concurrency::OSThread
{
public:
static const uint32_t c_longPressTime = 5000; // shutdown after 5s
static const uint32_t c_holdOffTime = 30000; // hold off 30s after boot
static const uint32_t c_holdOffTime = 30000; // hold off 30s after boot
enum ButtonEventType {
BUTTON_EVENT_NONE,

View File

@@ -212,8 +212,23 @@ void fsInit()
LOG_ERROR("Filesystem mount Failed.\n");
// assert(0); This auto-formats the partition, so no need to fail here.
}
#ifdef ARCH_ESP32
#if defined(ARCH_ESP32)
LOG_DEBUG("Filesystem files (%d/%d Bytes):\n", FSCom.usedBytes(), FSCom.totalBytes());
#elif defined(ARCH_NRF52)
/*
* nRF52840 has a certain chance of automatic formatting failure.
* Try to create a file after initializing the file system. If the creation fails,
* it means that the file system is not working properly. Please format it manually again.
* */
Adafruit_LittleFS_Namespace::File file(FSCom);
const char *filename = "/meshtastic.txt";
if (!file.open(filename, FILE_O_WRITE)) {
LOG_DEBUG("Format ....");
FSCom.format();
FSCom.begin();
} else {
file.close();
}
#else
LOG_DEBUG("Filesystem files:\n");
#endif

View File

@@ -69,7 +69,7 @@ static const uint8_t ext_chrg_detect_value = EXT_CHRG_DETECT_VALUE;
#endif
#endif
#if HAS_TELEMETRY && !defined(ARCH_PORTDUINO)
#if HAS_TELEMETRY && !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR && !defined(ARCH_PORTDUINO)
INA260Sensor ina260Sensor;
INA219Sensor ina219Sensor;
INA3221Sensor ina3221Sensor;
@@ -184,7 +184,7 @@ class AnalogBatteryLevel : public HasBatteryLevel
virtual uint16_t getBattVoltage() override
{
#if HAS_TELEMETRY && !defined(ARCH_PORTDUINO) && !defined(HAS_PMU)
#if HAS_TELEMETRY && !defined(ARCH_PORTDUINO) && !defined(HAS_PMU) && !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
if (hasINA()) {
LOG_DEBUG("Using INA on I2C addr 0x%x for device battery voltage\n", config.power.device_battery_ina_address);
return getINAVoltage();
@@ -372,7 +372,7 @@ class AnalogBatteryLevel : public HasBatteryLevel
float last_read_value = (OCV[NUM_OCV_POINTS - 1] * NUM_CELLS);
uint32_t last_read_time_ms = 0;
#if HAS_TELEMETRY && !defined(ARCH_PORTDUINO)
#if HAS_TELEMETRY && !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR && !defined(ARCH_PORTDUINO)
uint16_t getINAVoltage()
{
if (nodeTelemetrySensorsMap[meshtastic_TelemetrySensorType_INA219].first == config.power.device_battery_ina_address) {

View File

@@ -2,6 +2,7 @@
#include "NodeDB.h"
#include "PowerFSM.h"
#include "configuration.h"
#include "time.h"
#ifdef RP2040_SLOW_CLOCK
#define Port Serial2
@@ -50,7 +51,9 @@ SerialConsole::SerialConsole() : StreamAPI(&Port), RedirectablePrint(&Port), con
}
}
#endif
#if !ARCH_PORTDUINO
emitRebooted();
#endif
}
int32_t SerialConsole::runOnce()

View File

@@ -126,8 +126,9 @@ along with this program. If not, see <http://www.gnu.org/licenses/>.
#define SHTC3_ADDR 0x70
#define LPS22HB_ADDR 0x5C
#define LPS22HB_ADDR_ALT 0x5D
#define SHT31_ADDR 0x44
#define SHT31_4x_ADDR 0x44
#define PMSA0031_ADDR 0x12
#define RCWL9620_ADDR 0x57
// -----------------------------------------------------------------------------
// ACCELEROMETER

View File

@@ -29,6 +29,7 @@ class ScanI2C
INA3221,
MCP9808,
SHT31,
SHT4X,
SHTC3,
LPS22HB,
QMC6310,
@@ -41,6 +42,7 @@ class ScanI2C
BQ24295,
LSM6DS3,
TCA9555,
RCWL9620,
NCP5623,
} DeviceType;

View File

@@ -292,8 +292,20 @@ void ScanI2CTwoWire::scanPort(I2CPort port)
break;
SCAN_SIMPLE_CASE(SHT31_ADDR, SHT31, "SHT31 sensor found\n")
case SHT31_4x_ADDR:
registerValue = getRegisterValue(ScanI2CTwoWire::RegisterLocation(addr, 0x89), 2);
if (registerValue == 0x11a2) {
type = SHT4X;
LOG_INFO("SHT4X sensor found\n");
} else {
type = SHT31;
LOG_INFO("SHT31 sensor found\n");
}
break;
SCAN_SIMPLE_CASE(SHTC3_ADDR, SHTC3, "SHTC3 sensor found\n")
SCAN_SIMPLE_CASE(RCWL9620_ADDR, RCWL9620, "RCWL9620 sensor found\n")
case LPS22HB_ADDR_ALT:
SCAN_SIMPLE_CASE(LPS22HB_ADDR, LPS22HB, "LPS22HB sensor found\n")
@@ -356,4 +368,4 @@ TwoWire *ScanI2CTwoWire::fetchI2CBus(ScanI2C::DeviceAddress address) const
size_t ScanI2CTwoWire::countDevices() const
{
return foundDevices.size();
}
}

View File

@@ -62,10 +62,10 @@ void GPS::CASChecksum(uint8_t *message, size_t length)
// Iterate over the payload as a series of uint32_t's and
// accumulate the cksum
uint32_t *payload = (uint32_t *)(message + 6);
uint32_t const *payload = (uint32_t *)(message + 6);
for (size_t i = 0; i < (length - 10) / 4; i++) {
uint32_t p = payload[i];
cksum += p;
uint32_t pl = payload[i];
cksum += pl;
}
// Place the checksum values in the message
@@ -452,7 +452,7 @@ bool GPS::setup()
// Set the NEMA output messages
// Ask for only RMC and GGA
uint8_t fields[] = {CAS_NEMA_RMC, CAS_NEMA_GGA};
for (uint i = 0; i < sizeof(fields); i++) {
for (unsigned int i = 0; i < sizeof(fields); i++) {
// Construct a CAS-CFG-MSG packet
uint8_t cas_cfg_msg_packet[] = {0x4e, fields[i], 0x01, 0x00};
msglen = makeCASPacket(0x06, 0x01, sizeof(cas_cfg_msg_packet), cas_cfg_msg_packet);
@@ -1584,7 +1584,7 @@ bool GPS::hasFlow()
bool GPS::whileIdle()
{
uint charsInBuf = 0;
unsigned int charsInBuf = 0;
bool isValid = false;
if (!isAwake) {
clearBuffer();

View File

@@ -94,6 +94,11 @@ std::vector<MeshModule *> moduleFrames;
// Stores the last 4 of our hardware ID, to make finding the device for pairing easier
static char ourId[5];
// vector where symbols (string) are displayed in bottom corner of display.
std::vector<std::string> functionSymbals;
// string displayed in bottom right corner of display. Created from elements in functionSymbals vector
std::string functionSymbalString = "";
#if HAS_GPS
// GeoCoord object for the screen
GeoCoord geoCoord;
@@ -260,6 +265,18 @@ static void drawWelcomeScreen(OLEDDisplay *display, OLEDDisplayUiState *state, i
#endif
}
// draw overlay in bottom right corner of screen to show when notifications are muted or modifier key is active
static void drawFunctionOverlay(OLEDDisplay *display, OLEDDisplayUiState *state)
{
// LOG_DEBUG("Drawing function overlay\n");
if (functionSymbals.begin() != functionSymbals.end()) {
char buf[64];
display->setFont(FONT_SMALL);
snprintf(buf, sizeof(buf), "%s", functionSymbalString.c_str());
display->drawString(SCREEN_WIDTH - display->getStringWidth(buf), SCREEN_HEIGHT - FONT_HEIGHT_SMALL, buf);
}
}
#ifdef USE_EINK
/// Used on eink displays while in deep sleep
static void drawDeepSleepScreen(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y)
@@ -1023,7 +1040,14 @@ void Screen::handleSetOn(bool on, FrameCallback einkScreensaver)
#if !ARCH_PORTDUINO
dispdev->displayOn();
#endif
#if defined(ST7789_CS) && \
!defined(M5STACK) // set display brightness when turning on screens. Just moved function from TFTDisplay to here.
static_cast<TFTDisplay *>(dispdev)->setDisplayBrightness(brightness);
#endif
dispdev->displayOn();
enabled = true;
setInterval(0); // Draw ASAP
runASAP = true;
@@ -1490,6 +1514,11 @@ void Screen::setFrames()
ui->setFrames(normalFrames, numframes);
ui->enableAllIndicators();
// Add function overlay here. This can show when notifications muted, modifier key is active etc
static OverlayCallback functionOverlay[] = {drawFunctionOverlay};
static const int functionOverlayCount = sizeof(functionOverlay) / sizeof(functionOverlay[0]);
ui->setOverlays(functionOverlay, functionOverlayCount);
prevFrame = -1; // Force drawNodeInfo to pick a new node (because our list
// just changed)
@@ -1573,9 +1602,55 @@ void Screen::blink()
delay(50);
count = count - 1;
}
// The dispdev->setBrightness does not work for t-deck display, it seems to run the setBrightness function in OLEDDisplay.
dispdev->setBrightness(brightness);
}
void Screen::increaseBrightness()
{
brightness = ((brightness + 62) > 254) ? brightness : (brightness + 62);
#if defined(ST7789_CS)
// run the setDisplayBrightness function. This works on t-decks
static_cast<TFTDisplay *>(dispdev)->setDisplayBrightness(brightness);
#endif
/* TO DO: add little popup in center of screen saying what brightness level it is set to*/
}
void Screen::decreaseBrightness()
{
brightness = (brightness < 70) ? brightness : (brightness - 62);
#if defined(ST7789_CS)
static_cast<TFTDisplay *>(dispdev)->setDisplayBrightness(brightness);
#endif
/* TO DO: add little popup in center of screen saying what brightness level it is set to*/
}
void Screen::setFunctionSymbal(std::string sym)
{
if (std::find(functionSymbals.begin(), functionSymbals.end(), sym) == functionSymbals.end()) {
functionSymbals.push_back(sym);
functionSymbalString = "";
for (auto symbol : functionSymbals) {
functionSymbalString = symbol + " " + functionSymbalString;
}
setFastFramerate();
}
}
void Screen::removeFunctionSymbal(std::string sym)
{
functionSymbals.erase(std::remove(functionSymbals.begin(), functionSymbals.end(), sym), functionSymbals.end());
functionSymbalString = "";
for (auto symbol : functionSymbals) {
functionSymbalString = symbol + " " + functionSymbalString;
}
setFastFramerate();
}
std::string Screen::drawTimeDelta(uint32_t days, uint32_t hours, uint32_t minutes, uint32_t seconds)
{
std::string uptime;
@@ -1998,4 +2073,4 @@ int Screen::handleInputEvent(const InputEvent *event)
} // namespace graphics
#else
graphics::Screen::Screen(ScanI2C::DeviceAddress, meshtastic_Config_DisplayConfig_OledType, OLEDDISPLAY_GEOMETRY) {}
#endif // HAS_SCREEN
#endif // HAS_SCREEN

View File

@@ -166,9 +166,6 @@ class Screen : public concurrency::OSThread
void showPrevFrame() { enqueueCmd(ScreenCmd{.cmd = Cmd::SHOW_PREV_FRAME}); }
void showNextFrame() { enqueueCmd(ScreenCmd{.cmd = Cmd::SHOW_NEXT_FRAME}); }
// Implementation to Adjust Brightness
uint8_t brightness = BRIGHTNESS_DEFAULT;
/// Starts showing the Bluetooth PIN screen.
//
// Switches over to a static frame showing the Bluetooth pairing screen
@@ -202,6 +199,13 @@ class Screen : public concurrency::OSThread
enqueueCmd(cmd);
}
// functions for display brightness
void increaseBrightness();
void decreaseBrightness();
void setFunctionSymbal(std::string sym);
void removeFunctionSymbal(std::string sym);
/// Stops showing the bluetooth PIN screen.
void stopBluetoothPinScreen() { enqueueCmd(ScreenCmd{.cmd = Cmd::STOP_BLUETOOTH_PIN_SCREEN}); }
@@ -395,6 +399,9 @@ class Screen : public concurrency::OSThread
// Bluetooth PIN screen)
bool showingNormalScreen = false;
// Implementation to Adjust Brightness
uint8_t brightness = BRIGHTNESS_DEFAULT; // H = 254, MH = 192, ML = 130 L = 103
/// Holds state for debug information
DebugInfo debugInfo;

View File

@@ -8,6 +8,12 @@
#define TFT_BACKLIGHT_ON HIGH
#endif
#ifdef GPIO_EXTENDER
#include <SparkFunSX1509.h>
#include <Wire.h>
extern SX1509 gpioExtender;
#endif
#ifndef TFT_MESH
#define TFT_MESH COLOR565(0x67, 0xEA, 0x94)
#endif
@@ -590,7 +596,7 @@ void TFTDisplay::sendCommand(uint8_t com)
unphone.backlight(true); // using unPhone library
#endif
#ifdef RAK14014
#elif !defined(M5STACK)
#elif !defined(M5STACK) && !defined(ST7789_CS) // T-Deck gets brightness set in Screen.cpp in the handleSetOn function
tft->setBrightness(172);
#endif
break;
@@ -634,6 +640,12 @@ void TFTDisplay::sendCommand(uint8_t com)
// Drop all other commands to device (we just update the buffer)
}
void TFTDisplay::setDisplayBrightness(uint8_t _brightness)
{
tft->setBrightness(_brightness);
LOG_DEBUG("Brightness is set to value: %i \n", _brightness);
}
void TFTDisplay::flipScreenVertically()
{
#if defined(T_WATCH_S3)

View File

@@ -30,6 +30,9 @@ class TFTDisplay : public OLEDDisplay
static bool hasTouch(void);
static bool getTouch(int16_t *x, int16_t *y);
// Functions for changing display brightness
void setDisplayBrightness(uint8_t);
/**
* shim to make the abstraction happy
*

View File

@@ -3,6 +3,7 @@
#include "InputBroker.h"
#include "concurrency/OSThread.h"
#include "mesh/NodeDB.h"
#include "time.h"
typedef struct _TouchEvent {
const char *source;

View File

@@ -1,5 +1,4 @@
#include "kbI2cBase.h"
#include "configuration.h"
#include "detect/ScanI2C.h"
@@ -138,6 +137,9 @@ int32_t KbI2cBase::runOnce()
break;
case 0x13: // Code scanner says the SYM key is 0x13
is_sym = !is_sym;
e.inputEvent = ANYKEY;
e.kbchar =
is_sym ? 0xf1 : 0xf2; // send 0xf1 to tell CannedMessages to display that the modifier key is active
break;
case 0x0a: // apparently Enter on Q10 is a line feed instead of carriage return
e.inputEvent = meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_SELECT;
@@ -193,6 +195,75 @@ int32_t KbI2cBase::runOnce()
e.inputEvent = meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_NONE;
e.source = this->_originName;
switch (c) {
case 0x71: // This is the button q. If modifier and q pressed, it cancels the input
if (is_sym) {
is_sym = false;
e.inputEvent = meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_CANCEL;
} else {
e.inputEvent = ANYKEY;
e.kbchar = c;
}
break;
case 0x74: // letter t. if modifier and t pressed call 'tab'
if (is_sym) {
is_sym = false;
e.inputEvent = ANYKEY;
e.kbchar = 0x09; // TAB Scancode
} else {
e.inputEvent = ANYKEY;
e.kbchar = c;
}
break;
case 0x6d: // letter m. Modifier makes it mute notifications
if (is_sym) {
is_sym = false;
e.inputEvent = ANYKEY;
e.kbchar = 0xac; // mute notifications
} else {
e.inputEvent = ANYKEY;
e.kbchar = c;
}
break;
case 0x6f: // letter o(+). Modifier makes screen increase in brightness
if (is_sym) {
is_sym = false;
e.inputEvent = ANYKEY;
e.kbchar = 0x11; // Increase Brightness code
} else {
e.inputEvent = ANYKEY;
e.kbchar = c;
}
break;
case 0x69: // letter i(-). Modifier makes screen decrease in brightness
if (is_sym) {
is_sym = false;
e.inputEvent = ANYKEY;
e.kbchar = 0x12; // Decrease Brightness code
} else {
e.inputEvent = ANYKEY;
e.kbchar = c;
}
break;
case 0x20: // Space. Send network ping like double press does
if (is_sym) {
is_sym = false;
e.inputEvent = ANYKEY;
e.kbchar = 0xaf; // (fn + space)
} else {
e.inputEvent = ANYKEY;
e.kbchar = c;
}
break;
case 0x67: // letter g. toggle gps
if (is_sym) {
is_sym = false;
e.inputEvent = ANYKEY;
e.kbchar = 0x9e;
} else {
e.inputEvent = ANYKEY;
e.kbchar = c;
}
break;
case 0x1b: // ESC
e.inputEvent = meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_CANCEL;
break;
@@ -216,6 +287,12 @@ int32_t KbI2cBase::runOnce()
e.inputEvent = meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_RIGHT;
e.kbchar = 0xb7;
break;
case 0xc: // Modifier key: 0xc is alt+c (Other options could be: 0xea = shift+mic button or 0x4 shift+$(speaker))
// toggle moddifiers button.
is_sym = !is_sym;
e.inputEvent = ANYKEY;
e.kbchar = is_sym ? 0xf1 : 0xf2; // send 0xf1 to tell CannedMessages to display that the modifier key is active
break;
case 0x90: // fn+r
case 0x91: // fn+t
case 0x9b: // fn+s
@@ -239,6 +316,7 @@ int32_t KbI2cBase::runOnce()
}
e.inputEvent = ANYKEY;
e.kbchar = c;
is_sym = false;
break;
}

View File

@@ -197,7 +197,9 @@ uint32_t timeLastPowered = 0;
static Periodic *ledPeriodic;
static OSThread *powerFSMthread;
#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
static OSThread *accelerometerThread;
#endif
static OSThread *ambientLightingThread;
SPISettings spiSettings(4000000, MSBFIRST, SPI_MODE0);
@@ -342,7 +344,7 @@ void setup()
Wire.begin(I2C_SDA, I2C_SCL);
#elif defined(ARCH_PORTDUINO)
if (settingsStrings[i2cdev] != "") {
LOG_INFO("Using %s as I2C device.\n", settingsStrings[i2cdev]);
LOG_INFO("Using %s as I2C device.\n", settingsStrings[i2cdev].c_str());
Wire.begin(settingsStrings[i2cdev].c_str());
} else {
LOG_INFO("No I2C device configured, skipping.\n");
@@ -538,6 +540,8 @@ void setup()
SCANNER_TO_SENSORS_MAP(ScanI2C::DeviceType::QMI8658, meshtastic_TelemetrySensorType_QMI8658)
SCANNER_TO_SENSORS_MAP(ScanI2C::DeviceType::QMC5883L, meshtastic_TelemetrySensorType_QMC5883L)
SCANNER_TO_SENSORS_MAP(ScanI2C::DeviceType::PMSA0031, meshtastic_TelemetrySensorType_PMSA003I)
SCANNER_TO_SENSORS_MAP(ScanI2C::DeviceType::RCWL9620, meshtastic_TelemetrySensorType_RCWL9620)
SCANNER_TO_SENSORS_MAP(ScanI2C::DeviceType::SHT4X, meshtastic_TelemetrySensorType_SHT4X)
i2cScanner.reset();
@@ -604,7 +608,7 @@ void setup()
screen_model = meshtastic_Config_DisplayConfig_OledType_OLED_SH1107; // keep dimension of 128x64
#endif
#if !defined(ARCH_PORTDUINO) && !defined(ARCH_STM32WL)
#if !defined(ARCH_PORTDUINO) && !defined(ARCH_STM32WL) && !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
if (acc_info.type != ScanI2C::DeviceType::NONE) {
config.display.wake_on_tap_or_motion = true;
moduleConfig.external_notification.enabled = true;
@@ -735,7 +739,8 @@ void setup()
if (settingsMap[use_sx1262]) {
if (!rIf) {
LOG_DEBUG("Attempting to activate sx1262 radio on SPI port %s\n", settingsStrings[spidev].c_str());
LockingArduinoHal *RadioLibHAL = new LockingArduinoHal(SPI, spiSettings);
LockingArduinoHal *RadioLibHAL =
new LockingArduinoHal(SPI, spiSettings, (settingsMap[ch341Quirk] ? settingsMap[busy] : RADIOLIB_NC));
rIf = new SX1262Interface((LockingArduinoHal *)RadioLibHAL, settingsMap[cs], settingsMap[irq], settingsMap[reset],
settingsMap[busy]);
if (!rIf->init()) {
@@ -749,7 +754,8 @@ void setup()
} else if (settingsMap[use_rf95]) {
if (!rIf) {
LOG_DEBUG("Attempting to activate rf95 radio on SPI port %s\n", settingsStrings[spidev].c_str());
LockingArduinoHal *RadioLibHAL = new LockingArduinoHal(SPI, spiSettings);
LockingArduinoHal *RadioLibHAL =
new LockingArduinoHal(SPI, spiSettings, (settingsMap[ch341Quirk] ? settingsMap[busy] : RADIOLIB_NC));
rIf = new RF95Interface((LockingArduinoHal *)RadioLibHAL, settingsMap[cs], settingsMap[irq], settingsMap[reset],
settingsMap[busy]);
if (!rIf->init()) {
@@ -1029,4 +1035,4 @@ void loop()
mainDelay.delay(delayMsec);
}
// if (didWake) LOG_DEBUG("wake!\n");
}
}

View File

@@ -192,9 +192,7 @@ void MeshService::handleToRadio(meshtastic_MeshPacket &p)
return;
}
#endif
if (p.from != 0) { // We don't let phones assign nodenums to their sent messages
p.from = 0;
}
p.from = 0; // We don't let phones assign nodenums to their sent messages
if (p.id == 0)
p.id = generatePacketId(); // If the phone didn't supply one, then pick one
@@ -259,7 +257,7 @@ void MeshService::sendToMesh(meshtastic_MeshPacket *p, RxSource src, bool ccToPh
LOG_DEBUG("Can't send status to phone");
}
if (ccToPhone) {
if (res == ERRNO_OK && ccToPhone) { // Check if p is not released in case it couldn't be sent
sendToPhone(packetPool.allocCopy(*p));
}
}

View File

@@ -56,7 +56,7 @@ meshtastic_OEMStore oemStore;
bool meshtastic_DeviceState_callback(pb_istream_t *istream, pb_ostream_t *ostream, const pb_field_iter_t *field)
{
if (ostream) {
std::vector<meshtastic_NodeInfoLite> *vec = (std::vector<meshtastic_NodeInfoLite> *)field->pData;
std::vector<meshtastic_NodeInfoLite> const *vec = (std::vector<meshtastic_NodeInfoLite> *)field->pData;
for (auto item : *vec) {
if (!pb_encode_tag_for_field(ostream, field))
return false;
@@ -269,7 +269,7 @@ void NodeDB::installDefaultConfig()
config.device.node_info_broadcast_secs = default_node_info_broadcast_secs;
config.device.serial_enabled = true;
resetRadioConfig();
strncpy(config.network.ntp_server, "0.pool.ntp.org", 32);
strncpy(config.network.ntp_server, "meshtastic.pool.ntp.org", 32);
// FIXME: Default to bluetooth capability of platform as default
config.bluetooth.enabled = true;
config.bluetooth.fixed_pin = defaultBLEPin;
@@ -449,7 +449,7 @@ void NodeDB::resetNodes()
neighborInfoModule->resetNeighbors();
}
void NodeDB::removeNodeByNum(uint nodeNum)
void NodeDB::removeNodeByNum(NodeNum nodeNum)
{
int newPos = 0, removed = 0;
for (int i = 0; i < numMeshNodes; i++) {

View File

@@ -124,7 +124,7 @@ class NodeDB
*/
size_t getNumOnlineMeshNodes(bool localOnly = false);
void initConfigIntervals(), initModuleConfigIntervals(), resetNodes(), removeNodeByNum(uint nodeNum);
void initConfigIntervals(), initModuleConfigIntervals(), resetNodes(), removeNodeByNum(NodeNum nodeNum);
bool factoryReset();

View File

@@ -95,12 +95,11 @@ template <class T> class ProtobufModule : protected SinglePortModule
*/
virtual void alterReceived(meshtastic_MeshPacket &mp) override
{
auto &p = mp.decoded;
T scratch;
T *decoded = NULL;
if (mp.which_payload_variant == meshtastic_MeshPacket_decoded_tag && mp.decoded.portnum == ourPortNum) {
memset(&scratch, 0, sizeof(scratch));
auto &p = mp.decoded;
if (pb_decode_from_bytes(p.payload.bytes, p.payload.size, fields, &scratch)) {
decoded = &scratch;
} else {

View File

@@ -495,7 +495,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());
// channel_num is actually (channel_num - 1), since modulus (%) returns values from 0 to (numChannels - 1)
uint channel_num = (loraConfig.channel_num ? loraConfig.channel_num - 1 : hash(channelName)) % numChannels;
uint32_t channel_num = (loraConfig.channel_num ? loraConfig.channel_num - 1 : hash(channelName)) % numChannels;
// Check if we use the default frequency slot
RadioInterface::uses_default_frequency_slot =

View File

@@ -25,7 +25,31 @@ void LockingArduinoHal::spiEndTransaction()
#if ARCH_PORTDUINO
void LockingArduinoHal::spiTransfer(uint8_t *out, size_t len, uint8_t *in)
{
spi->transfer(out, in, len);
if (busy == RADIOLIB_NC) {
spi->transfer(out, in, len);
} else {
uint16_t offset = 0;
while (len) {
uint8_t block_size = (len < 20 ? len : 20);
spi->transfer((out != NULL ? out + offset : NULL), (in != NULL ? in + offset : NULL), block_size);
if (block_size == len)
return;
// ensure GPIO is low
uint32_t start = millis();
while (digitalRead(busy)) {
if (millis() - start >= 2000) {
LOG_ERROR("GPIO mid-transfer timeout, is it connected?");
return;
}
}
offset += block_size;
len -= block_size;
}
}
}
#endif
@@ -414,4 +438,4 @@ void RadioLibInterface::startSend(meshtastic_MeshPacket *txp)
// bits
enableInterrupt(isrTxLevel0);
}
}
}

View File

@@ -21,12 +21,20 @@
class LockingArduinoHal : public ArduinoHal
{
public:
LockingArduinoHal(SPIClass &spi, SPISettings spiSettings) : ArduinoHal(spi, spiSettings){};
LockingArduinoHal(SPIClass &spi, SPISettings spiSettings, RADIOLIB_PIN_TYPE _busy = RADIOLIB_NC)
: ArduinoHal(spi, spiSettings)
{
#if ARCH_PORTDUINO
busy = _busy;
#endif
};
void spiBeginTransaction() override;
void spiEndTransaction() override;
#if ARCH_PORTDUINO
RADIOLIB_PIN_TYPE busy;
void spiTransfer(uint8_t *out, size_t len, uint8_t *in) override;
#endif
};
@@ -179,4 +187,4 @@ class RadioLibInterface : public RadioInterface, protected concurrency::Notified
virtual void addReceiveMetadata(meshtastic_MeshPacket *mp) = 0;
virtual void setStandby() = 0;
};
};

View File

@@ -63,6 +63,8 @@ typedef enum _meshtastic_HardwareModel {
meshtastic_HardwareModel_NANO_G2_ULTRA = 18,
/* LoRAType device: https://loratype.org/ */
meshtastic_HardwareModel_LORA_TYPE = 19,
/* wiphone https://www.wiphone.io/ */
meshtastic_HardwareModel_WIPHONE = 20,
/* B&Q Consulting Station Edition G1: https://uniteng.com/wiki/doku.php?id=meshtastic:station */
meshtastic_HardwareModel_STATION_G1 = 25,
/* RAK11310 (RP2040 + SX1262) */
@@ -151,6 +153,9 @@ typedef enum _meshtastic_HardwareModel {
/* TWC_MESH_V4
Adafruit NRF52840 feather express with SX1262, SSD1306 OLED and NEO6M GPS */
meshtastic_HardwareModel_TWC_MESH_V4 = 62,
/* NRF52_PROMICRO_DIY
Promicro NRF52840 with SX1262/LLCC68, SSD1306 OLED and NEO6M GPS */
meshtastic_HardwareModel_NRF52_PROMICRO_DIY = 63,
/* ------------------------------------------------------------------------------------------------------------------------------------------
Reserved ID For developing private Ports. These will show up in live traffic sparsely, so we can use a high number. Keep it within 8 bits.
------------------------------------------------------------------------------------------------------------------------------------------ */

View File

@@ -45,7 +45,9 @@ typedef enum _meshtastic_TelemetrySensorType {
/* BMP085/BMP180 High accuracy temperature and pressure (older Version of BMP280) */
meshtastic_TelemetrySensorType_BMP085 = 15,
/* RCWL-9620 Doppler Radar Distance Sensor, used for water level detection */
meshtastic_TelemetrySensorType_RCWL9620 = 16
meshtastic_TelemetrySensorType_RCWL9620 = 16,
/* Sensirion High accuracy temperature and humidity */
meshtastic_TelemetrySensorType_SHT4X = 17
} meshtastic_TelemetrySensorType;
/* Struct definitions */
@@ -152,8 +154,8 @@ extern "C" {
/* Helper constants for enums */
#define _meshtastic_TelemetrySensorType_MIN meshtastic_TelemetrySensorType_SENSOR_UNSET
#define _meshtastic_TelemetrySensorType_MAX meshtastic_TelemetrySensorType_RCWL9620
#define _meshtastic_TelemetrySensorType_ARRAYSIZE ((meshtastic_TelemetrySensorType)(meshtastic_TelemetrySensorType_RCWL9620+1))
#define _meshtastic_TelemetrySensorType_MAX meshtastic_TelemetrySensorType_SHT4X
#define _meshtastic_TelemetrySensorType_ARRAYSIZE ((meshtastic_TelemetrySensorType)(meshtastic_TelemetrySensorType_SHT4X+1))

View File

@@ -221,6 +221,8 @@ bool AdminModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshta
nodeDB->setLocalPosition(r->set_fixed_position);
config.position.fixed_position = true;
saveChanges(SEGMENT_DEVICESTATE | SEGMENT_CONFIG, false);
// Send our new fixed position to the mesh for good measure
positionModule->sendOurPosition();
#if !MESHTASTIC_EXCLUDE_GPS
if (gps != nullptr)
gps->enable();

View File

@@ -180,11 +180,75 @@ int CannedMessageModule::handleInputEvent(const InputEvent *event)
(this->runState == CANNED_MESSAGE_RUN_STATE_DISABLED)) {
this->runState = CANNED_MESSAGE_RUN_STATE_FREETEXT;
}
// pass the pressed key
// LOG_DEBUG("Canned message ANYKEY (%x)\n", event->kbchar);
this->payload = event->kbchar;
this->lastTouchMillis = millis();
validEvent = true;
validEvent = false; // If key is normal than it will be set to true.
// Run modifier key code below, (doesnt inturrupt typing or reset to start screen page)
switch (event->kbchar) {
case 0x11: // make screen brighter
if (screen)
screen->increaseBrightness();
LOG_DEBUG("increasing Screen Brightness\n");
break;
case 0x12: // make screen dimmer
if (screen)
screen->decreaseBrightness();
LOG_DEBUG("Decreasing Screen Brightness\n");
break;
case 0xf1: // draw modifier (function) symbal
if (screen)
screen->setFunctionSymbal("Fn");
break;
case 0xf2: // remove modifier (function) symbal
if (screen)
screen->removeFunctionSymbal("Fn");
break;
// mute (switch off/toggle) external notifications on fn+m
case 0xac:
if (moduleConfig.external_notification.enabled == true) {
if (externalNotificationModule->getMute()) {
externalNotificationModule->setMute(false);
showTemporaryMessage("Notifications \nEnabled");
if (screen)
screen->removeFunctionSymbal("M"); // remove the mute symbol from the bottom right corner
} else {
externalNotificationModule->stopNow(); // this will turn off all GPIO and sounds and idle the loop
externalNotificationModule->setMute(true);
showTemporaryMessage("Notifications \nDisabled");
if (screen)
screen->setFunctionSymbal("M"); // add the mute symbol to the bottom right corner
}
}
break;
case 0x9e: // toggle GPS like triple press does
#if !MESHTASTIC_EXCLUDE_GPS
if (gps != nullptr) {
gps->toggleGpsMode();
}
if (screen)
screen->forceDisplay();
showTemporaryMessage("GPS Toggled");
#endif
break;
case 0xaf: // fn+space send network ping like double press does
service.refreshLocalMeshNode();
if (service.trySendPosition(NODENUM_BROADCAST, true)) {
showTemporaryMessage("Position \nUpdate Sent");
} else {
showTemporaryMessage("Node Info \nUpdate Sent");
}
break;
default:
// pass the pressed key
// LOG_DEBUG("Canned message ANYKEY (%x)\n", event->kbchar);
this->payload = event->kbchar;
this->lastTouchMillis = millis();
validEvent = true;
break;
}
if (screen && (event->kbchar != 0xf1)) {
screen->removeFunctionSymbal("Fn"); // remove modifier (function) symbal
}
}
if (event->inputEvent == static_cast<char>(MATRIXKEY)) {
LOG_DEBUG("Canned message event Matrix key pressed\n");
@@ -390,8 +454,9 @@ int32_t CannedMessageModule::runOnce()
}
if (this->runState == CANNED_MESSAGE_RUN_STATE_FREETEXT) {
e.frameChanged = true;
switch (this->payload) {
case 0x08: // backspace
switch (this->payload) { // code below all trigger the freetext window (where you type to send a message) or reset the
// display back to the default window
case 0x08: // backspace
if (this->freetext.length() > 0) {
if (this->cursor == this->freetext.length()) {
this->freetext = this->freetext.substring(0, this->freetext.length() - 1);
@@ -403,7 +468,6 @@ int32_t CannedMessageModule::runOnce()
}
break;
case 0x09: // tab
case 0x91: // alt+t for T-Deck that doesn't have a tab key
if (this->destSelect == CANNED_MESSAGE_DESTINATION_TYPE_CHANNEL) {
this->destSelect = CANNED_MESSAGE_DESTINATION_TYPE_NONE;
} else if (this->destSelect == CANNED_MESSAGE_DESTINATION_TYPE_NODE) {
@@ -416,7 +480,7 @@ int32_t CannedMessageModule::runOnce()
case 0xb7: // right
// already handled above
break;
// handle fn+s for shutdown
// handle fn+s for shutdown
case 0x9b:
if (screen)
screen->startShutdownScreen();
@@ -430,36 +494,6 @@ int32_t CannedMessageModule::runOnce()
rebootAtMsec = millis() + DEFAULT_REBOOT_SECONDS * 1000;
runState = CANNED_MESSAGE_RUN_STATE_INACTIVE;
break;
case 0x9e: // toggle GPS like triple press does
if (gps != nullptr) {
gps->toggleGpsMode();
}
if (screen)
screen->forceDisplay();
showTemporaryMessage("GPS Toggled");
break;
// mute (switch off/toggle) external notifications on fn+m
case 0xac:
if (moduleConfig.external_notification.enabled == true) {
if (externalNotificationModule->getMute()) {
externalNotificationModule->setMute(false);
showTemporaryMessage("Notifications \nEnabled");
} else {
externalNotificationModule->stopNow(); // this will turn off all GPIO and sounds and idle the loop
externalNotificationModule->setMute(true);
showTemporaryMessage("Notifications \nDisabled");
}
}
break;
case 0xaf: // fn+space send network ping like double press does
service.refreshLocalMeshNode();
if (service.trySendPosition(NODENUM_BROADCAST, true)) {
showTemporaryMessage("Position \nUpdate Sent");
} else {
showTemporaryMessage("Node Info \nUpdate Sent");
}
break;
default:
if (this->cursor == this->freetext.length()) {
this->freetext += this->payload;
@@ -475,6 +509,8 @@ int32_t CannedMessageModule::runOnce()
}
break;
}
if (screen)
screen->removeFunctionSymbal("Fn");
}
this->lastTouchMillis = millis();
@@ -786,4 +822,4 @@ String CannedMessageModule::drawWithCursor(String text, int cursor)
return result;
}
#endif
#endif

View File

@@ -45,7 +45,7 @@
#include "modules/Telemetry/AirQualityTelemetry.h"
#include "modules/Telemetry/EnvironmentTelemetry.h"
#endif
#if HAS_TELEMETRY && !defined(ARCH_PORTDUINO) && !MESHTASTIC_EXCLUDE_POWER_TELEMETRY
#if HAS_TELEMETRY && !MESHTASTIC_EXCLUDE_POWER_TELEMETRY
#include "modules/Telemetry/PowerTelemetry.h"
#endif
#ifdef ARCH_ESP32
@@ -137,7 +137,7 @@ void setupModules()
#if HAS_SCREEN && !MESHTASTIC_EXCLUDE_CANNEDMESSAGES
cannedMessageModule = new CannedMessageModule();
#endif
#if HAS_TELEMETRY && !defined(ARCH_PORTDUINO)
#if HAS_TELEMETRY
new DeviceTelemetryModule();
#endif
#if HAS_SENSOR && !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
@@ -146,7 +146,7 @@ void setupModules()
new AirQualityTelemetryModule();
}
#endif
#if HAS_TELEMETRY && !defined(ARCH_PORTDUINO) && !MESHTASTIC_EXCLUDE_POWER_TELEMETRY
#if HAS_TELEMETRY && !MESHTASTIC_EXCLUDE_POWER_TELEMETRY && !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
new PowerTelemetryModule();
#endif
#if (defined(ARCH_ESP32) || defined(ARCH_NRF52) || defined(ARCH_RP2040)) && !defined(CONFIG_IDF_TARGET_ESP32S2) && \

View File

@@ -116,9 +116,8 @@ Will be used for broadcast.
*/
int32_t NeighborInfoModule::runOnce()
{
bool requestReplies = false;
if (airTime->isTxAllowedChannelUtil(true) && airTime->isTxAllowedAirUtil()) {
sendNeighborInfo(NODENUM_BROADCAST, requestReplies);
sendNeighborInfo(NODENUM_BROADCAST, false);
}
return Default::getConfiguredOrDefaultMs(moduleConfig.neighbor_info.update_interval, default_broadcast_interval_secs);
}

View File

@@ -343,7 +343,7 @@ int32_t PositionModule::runOnce()
// The minimum time (in seconds) that would pass before we are able to send a new position packet.
auto smartPosition = getDistanceTraveledSinceLastSend(node->position);
uint32_t msSinceLastSend = now - lastGpsSend;
msSinceLastSend = now - lastGpsSend;
if (smartPosition.hasTraveledOverThreshold &&
Throttle::execute(

View File

@@ -1,12 +1,15 @@
#include "AirQualityTelemetry.h"
#include "configuration.h"
#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "AirQualityTelemetry.h"
#include "Default.h"
#include "MeshService.h"
#include "NodeDB.h"
#include "PowerFSM.h"
#include "RTC.h"
#include "Router.h"
#include "configuration.h"
#include "main.h"
int32_t AirQualityTelemetryModule::runOnce()
@@ -130,3 +133,5 @@ bool AirQualityTelemetryModule::sendTelemetry(NodeNum dest, bool phoneOnly)
}
return true;
}
#endif

View File

@@ -1,3 +1,7 @@
#include "configuration.h"
#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
#pragma once
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "Adafruit_PM25AQI.h"
@@ -35,3 +39,5 @@ class AirQualityTelemetryModule : private concurrency::OSThread, public Protobuf
uint32_t sendToPhoneIntervalMs = SECONDS_IN_MINUTE * 1000; // Send to phone every minute
uint32_t lastSentToMesh = 0;
};
#endif

View File

@@ -1,12 +1,15 @@
#include "EnvironmentTelemetry.h"
#include "configuration.h"
#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "Default.h"
#include "EnvironmentTelemetry.h"
#include "MeshService.h"
#include "NodeDB.h"
#include "PowerFSM.h"
#include "RTC.h"
#include "Router.h"
#include "configuration.h"
#include "main.h"
#include "power.h"
#include "sleep.h"
@@ -21,7 +24,9 @@
#include "Sensor/BMP280Sensor.h"
#include "Sensor/LPS22HBSensor.h"
#include "Sensor/MCP9808Sensor.h"
#include "Sensor/RCWL9620Sensor.h"
#include "Sensor/SHT31Sensor.h"
#include "Sensor/SHT4XSensor.h"
#include "Sensor/SHTC3Sensor.h"
BMP085Sensor bmp085Sensor;
@@ -32,6 +37,8 @@ MCP9808Sensor mcp9808Sensor;
SHTC3Sensor shtc3Sensor;
LPS22HBSensor lps22hbSensor;
SHT31Sensor sht31Sensor;
SHT4XSensor sht4xSensor;
RCWL9620Sensor rcwl9620Sensor;
#define FAILED_STATE_SENSOR_READ_MULTIPLIER 10
#define DISPLAY_RECEIVEID_MEASUREMENTS_ON_SCREEN true
@@ -86,10 +93,14 @@ int32_t EnvironmentTelemetryModule::runOnce()
result = lps22hbSensor.runOnce();
if (sht31Sensor.hasSensor())
result = sht31Sensor.runOnce();
if (sht4xSensor.hasSensor())
result = sht4xSensor.runOnce();
if (ina219Sensor.hasSensor())
result = ina219Sensor.runOnce();
if (ina260Sensor.hasSensor())
result = ina260Sensor.runOnce();
if (rcwl9620Sensor.hasSensor())
result = rcwl9620Sensor.runOnce();
}
return result;
} else {
@@ -144,45 +155,56 @@ uint32_t GetTimeSinceMeshPacket(const meshtastic_MeshPacket *mp)
void EnvironmentTelemetryModule::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y)
{
display->setTextAlignment(TEXT_ALIGN_LEFT);
display->setFont(FONT_MEDIUM);
display->drawString(x, y, "Environment");
display->setFont(FONT_SMALL);
if (lastMeasurementPacket == nullptr) {
display->setFont(FONT_SMALL);
display->drawString(x, y += fontHeight(FONT_MEDIUM), "No measurement");
// If there's no valid packet, display "Environment"
display->drawString(x, y, "Environment");
display->drawString(x, y += fontHeight(FONT_SMALL), "No measurement");
return;
}
// Decode the last measurement packet
meshtastic_Telemetry lastMeasurement;
uint32_t agoSecs = GetTimeSinceMeshPacket(lastMeasurementPacket);
const char *lastSender = getSenderShortName(*lastMeasurementPacket);
auto &p = lastMeasurementPacket->decoded;
if (!pb_decode_from_bytes(p.payload.bytes, p.payload.size, &meshtastic_Telemetry_msg, &lastMeasurement)) {
display->setFont(FONT_SMALL);
display->drawString(x, y += fontHeight(FONT_MEDIUM), "Measurement Error");
display->drawString(x, y, "Measurement Error");
LOG_ERROR("Unable to decode last packet");
return;
}
display->setFont(FONT_SMALL);
// Display "Env. From: ..." on its own
display->drawString(x, y, "Env. From: " + String(lastSender) + "(" + String(agoSecs) + "s)");
String last_temp = String(lastMeasurement.variant.environment_metrics.temperature, 0) + "°C";
if (moduleConfig.telemetry.environment_display_fahrenheit) {
last_temp = String(CelsiusToFahrenheit(lastMeasurement.variant.environment_metrics.temperature), 0) + "°F";
}
display->drawString(x, y += fontHeight(FONT_MEDIUM) - 2, "From: " + String(lastSender) + "(" + String(agoSecs) + "s)");
display->drawString(x, y += fontHeight(FONT_SMALL) - 2,
// Continue with the remaining details
display->drawString(x, y += fontHeight(FONT_SMALL),
"Temp/Hum: " + last_temp + " / " +
String(lastMeasurement.variant.environment_metrics.relative_humidity, 0) + "%");
if (lastMeasurement.variant.environment_metrics.barometric_pressure != 0)
if (lastMeasurement.variant.environment_metrics.barometric_pressure != 0) {
display->drawString(x, y += fontHeight(FONT_SMALL),
"Press: " + String(lastMeasurement.variant.environment_metrics.barometric_pressure, 0) + "hPA");
if (lastMeasurement.variant.environment_metrics.voltage != 0)
}
if (lastMeasurement.variant.environment_metrics.voltage != 0) {
display->drawString(x, y += fontHeight(FONT_SMALL),
"Volt/Cur: " + String(lastMeasurement.variant.environment_metrics.voltage, 0) + "V / " +
String(lastMeasurement.variant.environment_metrics.current, 0) + "mA");
if (lastMeasurement.variant.environment_metrics.iaq != 0)
}
if (lastMeasurement.variant.environment_metrics.iaq != 0) {
display->drawString(x, y += fontHeight(FONT_SMALL), "IAQ: " + String(lastMeasurement.variant.environment_metrics.iaq));
}
if (lastMeasurement.variant.environment_metrics.distance != 0)
display->drawString(x, y += fontHeight(FONT_SMALL),
"Water Level: " + String(lastMeasurement.variant.environment_metrics.distance, 0) + "mm");
}
bool EnvironmentTelemetryModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshtastic_Telemetry *t)
@@ -192,10 +214,13 @@ bool EnvironmentTelemetryModule::handleReceivedProtobuf(const meshtastic_MeshPac
const char *sender = getSenderShortName(mp);
LOG_INFO("(Received from %s): barometric_pressure=%f, current=%f, gas_resistance=%f, relative_humidity=%f, "
"temperature=%f, voltage=%f\n",
"temperature=%f\n",
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);
t->variant.environment_metrics.temperature);
LOG_INFO("(Received from %s): voltage=%f, IAQ=%d, distance=%f\n", sender, t->variant.environment_metrics.voltage,
t->variant.environment_metrics.iaq, t->variant.environment_metrics.distance);
#endif
// release previous packet before occupying a new spot
if (lastMeasurementPacket != nullptr)
@@ -220,9 +245,13 @@ bool EnvironmentTelemetryModule::sendTelemetry(NodeNum dest, bool phoneOnly)
m.variant.environment_metrics.relative_humidity = 0;
m.variant.environment_metrics.temperature = 0;
m.variant.environment_metrics.voltage = 0;
m.variant.environment_metrics.iaq = 0;
m.variant.environment_metrics.distance = 0;
if (sht31Sensor.hasSensor())
valid = sht31Sensor.getMetrics(&m);
if (sht4xSensor.hasSensor())
valid = sht4xSensor.getMetrics(&m);
if (lps22hbSensor.hasSensor())
valid = lps22hbSensor.getMetrics(&m);
if (shtc3Sensor.hasSensor())
@@ -241,13 +270,16 @@ bool EnvironmentTelemetryModule::sendTelemetry(NodeNum dest, bool phoneOnly)
valid = ina219Sensor.getMetrics(&m);
if (ina260Sensor.hasSensor())
valid = ina260Sensor.getMetrics(&m);
if (rcwl9620Sensor.hasSensor())
valid = rcwl9620Sensor.getMetrics(&m);
if (valid) {
LOG_INFO("(Sending): barometric_pressure=%f, current=%f, gas_resistance=%f, relative_humidity=%f, temperature=%f, "
"voltage=%f\n",
LOG_INFO("(Sending): barometric_pressure=%f, current=%f, gas_resistance=%f, relative_humidity=%f, temperature=%f\n",
m.variant.environment_metrics.barometric_pressure, m.variant.environment_metrics.current,
m.variant.environment_metrics.gas_resistance, m.variant.environment_metrics.relative_humidity,
m.variant.environment_metrics.temperature, m.variant.environment_metrics.voltage);
m.variant.environment_metrics.temperature);
LOG_INFO("(Sending): voltage=%f, IAQ=%d, distance=%f\n", m.variant.environment_metrics.voltage,
m.variant.environment_metrics.iaq, m.variant.environment_metrics.distance);
sensor_read_error_count = 0;
@@ -278,4 +310,6 @@ bool EnvironmentTelemetryModule::sendTelemetry(NodeNum dest, bool phoneOnly)
}
}
return valid;
}
}
#endif

View File

@@ -1,3 +1,7 @@
#include "configuration.h"
#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
#pragma once
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "NodeDB.h"
@@ -42,3 +46,5 @@ class EnvironmentTelemetryModule : private concurrency::OSThread, public Protobu
uint32_t lastSentToPhone = 0;
uint32_t sensor_read_error_count = 0;
};
#endif

View File

@@ -1,12 +1,15 @@
#include "PowerTelemetry.h"
#include "configuration.h"
#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "Default.h"
#include "MeshService.h"
#include "NodeDB.h"
#include "PowerFSM.h"
#include "PowerTelemetry.h"
#include "RTC.h"
#include "Router.h"
#include "configuration.h"
#include "main.h"
#include "power.h"
#include "sleep.h"
@@ -217,4 +220,6 @@ bool PowerTelemetryModule::sendTelemetry(NodeNum dest, bool phoneOnly)
}
}
return valid;
}
}
#endif

View File

@@ -1,4 +1,9 @@
#pragma once
#include "configuration.h"
#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "NodeDB.h"
#include "ProtobufModule.h"
@@ -41,3 +46,5 @@ class PowerTelemetryModule : private concurrency::OSThread, public ProtobufModul
uint32_t lastSentToPhone = 0;
uint32_t sensor_read_error_count = 0;
};
#endif

View File

@@ -1,7 +1,10 @@
#include "BME280Sensor.h"
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "TelemetrySensor.h"
#include "configuration.h"
#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "BME280Sensor.h"
#include "TelemetrySensor.h"
#include <Adafruit_BME280.h>
#include <typeinfo>
@@ -35,4 +38,5 @@ bool BME280Sensor::getMetrics(meshtastic_Telemetry *measurement)
measurement->variant.environment_metrics.barometric_pressure = bme280.readPressure() / 100.0F;
return true;
}
}
#endif

View File

@@ -1,3 +1,7 @@
#include "configuration.h"
#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "TelemetrySensor.h"
#include <Adafruit_BME280.h>
@@ -14,4 +18,6 @@ class BME280Sensor : public TelemetrySensor
BME280Sensor();
virtual int32_t runOnce() override;
virtual bool getMetrics(meshtastic_Telemetry *measurement) override;
};
};
#endif

View File

@@ -1,8 +1,11 @@
#include "BME680Sensor.h"
#include "configuration.h"
#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "BME680Sensor.h"
#include "FSCommon.h"
#include "TelemetrySensor.h"
#include "configuration.h"
BME680Sensor::BME680Sensor() : TelemetrySensor(meshtastic_TelemetrySensorType_BME680, "BME680") {}
@@ -134,3 +137,5 @@ void BME680Sensor::checkStatus(String functionName)
else if (bme680.sensor.status > BME68X_OK)
LOG_WARN("%s BME68X code: %s\n", functionName.c_str(), String(bme680.sensor.status).c_str());
}
#endif

View File

@@ -1,3 +1,7 @@
#include "configuration.h"
#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "TelemetrySensor.h"
#include <bsec2.h>
@@ -35,4 +39,6 @@ class BME680Sensor : public TelemetrySensor
int32_t runTrigger();
virtual int32_t runOnce() override;
virtual bool getMetrics(meshtastic_Telemetry *measurement) override;
};
};
#endif

View File

@@ -1,7 +1,10 @@
#include "BMP085Sensor.h"
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "TelemetrySensor.h"
#include "configuration.h"
#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "BMP085Sensor.h"
#include "TelemetrySensor.h"
#include <Adafruit_BMP085.h>
#include <typeinfo>
@@ -29,3 +32,5 @@ bool BMP085Sensor::getMetrics(meshtastic_Telemetry *measurement)
return true;
}
#endif

View File

@@ -1,3 +1,7 @@
#include "configuration.h"
#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "TelemetrySensor.h"
#include <Adafruit_BMP085.h>
@@ -14,4 +18,6 @@ class BMP085Sensor : public TelemetrySensor
BMP085Sensor();
virtual int32_t runOnce() override;
virtual bool getMetrics(meshtastic_Telemetry *measurement) override;
};
};
#endif

View File

@@ -1,7 +1,10 @@
#include "BMP280Sensor.h"
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "TelemetrySensor.h"
#include "configuration.h"
#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "BMP280Sensor.h"
#include "TelemetrySensor.h"
#include <Adafruit_BMP280.h>
#include <typeinfo>
@@ -35,3 +38,5 @@ bool BMP280Sensor::getMetrics(meshtastic_Telemetry *measurement)
return true;
}
#endif

View File

@@ -1,3 +1,7 @@
#include "configuration.h"
#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "TelemetrySensor.h"
#include <Adafruit_BMP280.h>
@@ -14,4 +18,6 @@ class BMP280Sensor : public TelemetrySensor
BMP280Sensor();
virtual int32_t runOnce() override;
virtual bool getMetrics(meshtastic_Telemetry *measurement) override;
};
};
#endif

View File

@@ -1,7 +1,10 @@
#include "INA219Sensor.h"
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "TelemetrySensor.h"
#include "configuration.h"
#if HAS_TELEMETRY && !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "INA219Sensor.h"
#include "TelemetrySensor.h"
#include <Adafruit_INA219.h>
#ifndef INA219_MULTIPLIER
@@ -37,4 +40,6 @@ bool INA219Sensor::getMetrics(meshtastic_Telemetry *measurement)
uint16_t INA219Sensor::getBusVoltageMv()
{
return lround(ina219.getBusVoltage_V() * 1000);
}
}
#endif

View File

@@ -1,3 +1,7 @@
#include "configuration.h"
#if HAS_TELEMETRY && !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "TelemetrySensor.h"
#include "VoltageSensor.h"
@@ -16,4 +20,6 @@ class INA219Sensor : public TelemetrySensor, VoltageSensor
virtual int32_t runOnce() override;
virtual bool getMetrics(meshtastic_Telemetry *measurement) override;
virtual uint16_t getBusVoltageMv() override;
};
};
#endif

View File

@@ -1,7 +1,10 @@
#include "INA260Sensor.h"
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "TelemetrySensor.h"
#include "configuration.h"
#if HAS_TELEMETRY && !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "INA260Sensor.h"
#include "TelemetrySensor.h"
#include <Adafruit_INA260.h>
INA260Sensor::INA260Sensor() : TelemetrySensor(meshtastic_TelemetrySensorType_INA260, "INA260") {}
@@ -32,4 +35,6 @@ bool INA260Sensor::getMetrics(meshtastic_Telemetry *measurement)
uint16_t INA260Sensor::getBusVoltageMv()
{
return lround(ina260.readBusVoltage());
}
}
#endif

View File

@@ -1,3 +1,7 @@
#include "configuration.h"
#if HAS_TELEMETRY && !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "TelemetrySensor.h"
#include "VoltageSensor.h"
@@ -16,4 +20,6 @@ class INA260Sensor : public TelemetrySensor, VoltageSensor
virtual int32_t runOnce() override;
virtual bool getMetrics(meshtastic_Telemetry *measurement) override;
virtual uint16_t getBusVoltageMv() override;
};
};
#endif

View File

@@ -1,7 +1,10 @@
#include "INA3221Sensor.h"
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "TelemetrySensor.h"
#include "configuration.h"
#if HAS_TELEMETRY && !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "INA3221Sensor.h"
#include "TelemetrySensor.h"
#include <INA3221.h>
INA3221Sensor::INA3221Sensor() : TelemetrySensor(meshtastic_TelemetrySensorType_INA3221, "INA3221"){};
@@ -41,4 +44,6 @@ bool INA3221Sensor::getMetrics(meshtastic_Telemetry *measurement)
uint16_t INA3221Sensor::getBusVoltageMv()
{
return lround(ina3221.getVoltage(INA3221_CH1) * 1000);
}
}
#endif

View File

@@ -1,3 +1,7 @@
#include "configuration.h"
#if HAS_TELEMETRY && !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "TelemetrySensor.h"
#include "VoltageSensor.h"
@@ -16,4 +20,6 @@ class INA3221Sensor : public TelemetrySensor, VoltageSensor
int32_t runOnce() override;
bool getMetrics(meshtastic_Telemetry *measurement) override;
virtual uint16_t getBusVoltageMv() override;
};
};
#endif

View File

@@ -1,7 +1,10 @@
#include "LPS22HBSensor.h"
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "TelemetrySensor.h"
#include "configuration.h"
#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "LPS22HBSensor.h"
#include "TelemetrySensor.h"
#include <Adafruit_LPS2X.h>
#include <Adafruit_Sensor.h>
@@ -32,4 +35,6 @@ bool LPS22HBSensor::getMetrics(meshtastic_Telemetry *measurement)
measurement->variant.environment_metrics.barometric_pressure = pressure.pressure;
return true;
}
}
#endif

View File

@@ -1,3 +1,7 @@
#include "configuration.h"
#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "TelemetrySensor.h"
#include <Adafruit_LPS2X.h>
@@ -15,4 +19,6 @@ class LPS22HBSensor : public TelemetrySensor
LPS22HBSensor();
virtual int32_t runOnce() override;
virtual bool getMetrics(meshtastic_Telemetry *measurement) override;
};
};
#endif

View File

@@ -1,7 +1,10 @@
#include "MCP9808Sensor.h"
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "TelemetrySensor.h"
#include "configuration.h"
#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "MCP9808Sensor.h"
#include "TelemetrySensor.h"
#include <Adafruit_MCP9808.h>
MCP9808Sensor::MCP9808Sensor() : TelemetrySensor(meshtastic_TelemetrySensorType_MCP9808, "MCP9808") {}
@@ -26,4 +29,6 @@ bool MCP9808Sensor::getMetrics(meshtastic_Telemetry *measurement)
LOG_DEBUG("MCP9808Sensor::getMetrics\n");
measurement->variant.environment_metrics.temperature = mcp9808.readTempC();
return true;
}
}
#endif

View File

@@ -1,3 +1,7 @@
#include "configuration.h"
#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "TelemetrySensor.h"
#include <Adafruit_MCP9808.h>
@@ -14,4 +18,6 @@ class MCP9808Sensor : public TelemetrySensor
MCP9808Sensor();
virtual int32_t runOnce() override;
virtual bool getMetrics(meshtastic_Telemetry *measurement) override;
};
};
#endif

View File

@@ -0,0 +1,65 @@
#include "configuration.h"
#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "RCWL9620Sensor.h"
#include "TelemetrySensor.h"
RCWL9620Sensor::RCWL9620Sensor() : TelemetrySensor(meshtastic_TelemetrySensorType_RCWL9620, "RCWL9620") {}
int32_t RCWL9620Sensor::runOnce()
{
LOG_INFO("Init sensor: %s\n", sensorName);
if (!hasSensor()) {
return DEFAULT_SENSOR_MINIMUM_WAIT_TIME_BETWEEN_READS;
}
status = 1;
begin(nodeTelemetrySensorsMap[sensorType].second, nodeTelemetrySensorsMap[sensorType].first);
return initI2CSensor();
}
void RCWL9620Sensor::setup() {}
bool RCWL9620Sensor::getMetrics(meshtastic_Telemetry *measurement)
{
LOG_DEBUG("RCWL9620Sensor::getMetrics\n");
measurement->variant.environment_metrics.distance = getDistance();
return true;
}
void RCWL9620Sensor::begin(TwoWire *wire, uint8_t addr, uint8_t sda, uint8_t scl, uint32_t speed)
{
_wire = wire;
_addr = addr;
_sda = sda;
_scl = scl;
_speed = speed;
_wire->begin();
}
float RCWL9620Sensor::getDistance()
{
uint32_t data;
_wire->beginTransmission(_addr); // Transfer data to addr.
_wire->write(0x01);
_wire->endTransmission(); // Stop data transmission with the Ultrasonic
// Unit.
_wire->requestFrom(_addr,
(uint8_t)3); // Request 3 bytes from Ultrasonic Unit.
data = _wire->read();
data <<= 8;
data |= _wire->read();
data <<= 8;
data |= _wire->read();
float Distance = float(data) / 1000;
if (Distance > 4500.00) {
return 4500.00;
} else {
return Distance;
}
}
#endif

View File

@@ -0,0 +1,29 @@
#include "configuration.h"
#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "TelemetrySensor.h"
#include <Wire.h>
class RCWL9620Sensor : public TelemetrySensor
{
private:
uint8_t _addr = 0x57;
TwoWire *_wire = &Wire;
uint8_t _scl = -1;
uint8_t _sda = -1;
uint32_t _speed = 200000UL;
protected:
virtual void setup() override;
void begin(TwoWire *wire = &Wire, uint8_t addr = 0x57, uint8_t sda = -1, uint8_t scl = -1, uint32_t speed = 200000UL);
float getDistance();
public:
RCWL9620Sensor();
virtual int32_t runOnce() override;
virtual bool getMetrics(meshtastic_Telemetry *measurement) override;
};
#endif

View File

@@ -1,7 +1,10 @@
#include "SHT31Sensor.h"
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "TelemetrySensor.h"
#include "configuration.h"
#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "SHT31Sensor.h"
#include "TelemetrySensor.h"
#include <Adafruit_SHT31.h>
SHT31Sensor::SHT31Sensor() : TelemetrySensor(meshtastic_TelemetrySensorType_SHT31, "SHT31") {}
@@ -29,3 +32,5 @@ bool SHT31Sensor::getMetrics(meshtastic_Telemetry *measurement)
return true;
}
#endif

View File

@@ -1,3 +1,7 @@
#include "configuration.h"
#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "TelemetrySensor.h"
#include <Adafruit_SHT31.h>
@@ -15,3 +19,5 @@ class SHT31Sensor : public TelemetrySensor
virtual int32_t runOnce() override;
virtual bool getMetrics(meshtastic_Telemetry *measurement) override;
};
#endif

View File

@@ -0,0 +1,63 @@
#include "configuration.h"
#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "SHT4XSensor.h"
#include "TelemetrySensor.h"
#include <SensirionI2cSht4x.h>
// macro definitions
// make sure that we use the proper definition of NO_ERROR
#ifdef NO_ERROR
#undef NO_ERROR
#endif
#define NO_ERROR 0
static char errorMessage[64];
static int16_t error;
SHT4XSensor::SHT4XSensor() : TelemetrySensor(meshtastic_TelemetrySensorType_SHT4X, "SHT4X") {}
int32_t SHT4XSensor::runOnce()
{
LOG_INFO("Init sensor: %s\n", sensorName);
if (!hasSensor()) {
return DEFAULT_SENSOR_MINIMUM_WAIT_TIME_BETWEEN_READS;
}
uint32_t serialNumber = 0;
sht4x.begin(*nodeTelemetrySensorsMap[sensorType].second, 0x44);
error = sht4x.serialNumber(serialNumber);
LOG_DEBUG("serialNumber : %x\n", serialNumber);
if (error != NO_ERROR) {
LOG_DEBUG("Error trying to execute serialNumber(): ");
errorToString(error, errorMessage, sizeof errorMessage);
LOG_DEBUG(errorMessage);
status = 0;
} else {
status = 1;
}
return initI2CSensor();
}
void SHT4XSensor::setup()
{
// Set up oversampling and filter initialization
}
bool SHT4XSensor::getMetrics(meshtastic_Telemetry *measurement)
{
float aTemperature = 0.0;
float aHumidity = 0.0;
sht4x.measureLowestPrecision(aTemperature, aHumidity);
measurement->variant.environment_metrics.temperature = aTemperature;
measurement->variant.environment_metrics.relative_humidity = aHumidity;
return true;
}
#endif

View File

@@ -0,0 +1,23 @@
#include "configuration.h"
#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "TelemetrySensor.h"
#include <SensirionI2cSht4x.h>
class SHT4XSensor : public TelemetrySensor
{
private:
SensirionI2cSht4x sht4x;
protected:
virtual void setup() override;
public:
SHT4XSensor();
virtual int32_t runOnce() override;
virtual bool getMetrics(meshtastic_Telemetry *measurement) override;
};
#endif

View File

@@ -1,7 +1,10 @@
#include "SHTC3Sensor.h"
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "TelemetrySensor.h"
#include "configuration.h"
#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "SHTC3Sensor.h"
#include "TelemetrySensor.h"
#include <Adafruit_SHTC3.h>
SHTC3Sensor::SHTC3Sensor() : TelemetrySensor(meshtastic_TelemetrySensorType_SHTC3, "SHTC3") {}
@@ -30,4 +33,6 @@ bool SHTC3Sensor::getMetrics(meshtastic_Telemetry *measurement)
measurement->variant.environment_metrics.relative_humidity = humidity.relative_humidity;
return true;
}
}
#endif

View File

@@ -1,3 +1,7 @@
#include "configuration.h"
#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "TelemetrySensor.h"
#include <Adafruit_SHTC3.h>
@@ -14,4 +18,6 @@ class SHTC3Sensor : public TelemetrySensor
SHTC3Sensor();
virtual int32_t runOnce() override;
virtual bool getMetrics(meshtastic_Telemetry *measurement) override;
};
};
#endif

View File

@@ -1,4 +1,10 @@
#include "TelemetrySensor.h"
#include "configuration.h"
#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "NodeDB.h"
#include "TelemetrySensor.h"
#include "main.h"
#endif

View File

@@ -1,3 +1,7 @@
#include "configuration.h"
#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
#pragma once
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "NodeDB.h"
@@ -45,4 +49,6 @@ class TelemetrySensor
virtual bool isRunning() { return status > 0; }
virtual bool getMetrics(meshtastic_Telemetry *measurement) = 0;
};
};
#endif

View File

@@ -1,7 +1,13 @@
#include "configuration.h"
#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
#pragma once
class VoltageSensor
{
public:
virtual uint16_t getBusVoltageMv() = 0;
};
};
#endif

View File

@@ -1,3 +1,5 @@
#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
#include "bsec_iaq.h"
const uint8_t bsec_config_iaq[1974] = {
@@ -80,3 +82,5 @@ const uint8_t bsec_config_iaq[1974] = {
255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 44, 1, 0, 5, 10, 5,
0, 2, 0, 10, 0, 30, 0, 5, 0, 5, 0, 5, 0, 5, 0, 5, 0, 5, 0, 64, 1, 100, 0, 100, 0,
100, 0, 200, 0, 200, 0, 200, 0, 64, 1, 64, 1, 64, 1, 10, 0, 0, 0, 0, 0, 21, 122, 0, 0};
#endif

View File

@@ -1,3 +1,7 @@
#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
#include <stdint.h>
extern const uint8_t bsec_config_iaq[1974];
#endif

View File

@@ -368,9 +368,9 @@ JSONValue::JSONValue(int m_integer_value)
*
* @access public
*
* @param uint m_integer_value The number to use as the value
* @param unsigned int m_integer_value The number to use as the value
*/
JSONValue::JSONValue(uint m_integer_value)
JSONValue::JSONValue(unsigned int m_integer_value)
{
type = JSONType_Number;
number_value = (double)m_integer_value;

View File

@@ -45,7 +45,7 @@ class JSONValue
JSONValue(bool m_bool_value);
JSONValue(double m_number_value);
JSONValue(int m_integer_value);
JSONValue(uint m_integer_value);
JSONValue(unsigned int m_integer_value);
JSONValue(const JSONArray &m_array_value);
JSONValue(const JSONObject &m_object_value);
JSONValue(const JSONValue &m_source);

View File

@@ -659,11 +659,11 @@ std::string MQTT::meshPacketToJson(meshtastic_MeshPacket *mp)
if (pb_decode_from_bytes(mp->decoded.payload.bytes, mp->decoded.payload.size, &meshtastic_Telemetry_msg, &scratch)) {
decoded = &scratch;
if (decoded->which_variant == meshtastic_Telemetry_device_metrics_tag) {
msgPayload["battery_level"] = new JSONValue((uint)decoded->variant.device_metrics.battery_level);
msgPayload["battery_level"] = new JSONValue((unsigned int)decoded->variant.device_metrics.battery_level);
msgPayload["voltage"] = new JSONValue(decoded->variant.device_metrics.voltage);
msgPayload["channel_utilization"] = new JSONValue(decoded->variant.device_metrics.channel_utilization);
msgPayload["air_util_tx"] = new JSONValue(decoded->variant.device_metrics.air_util_tx);
msgPayload["uptime_seconds"] = new JSONValue((uint)decoded->variant.device_metrics.uptime_seconds);
msgPayload["uptime_seconds"] = new JSONValue((unsigned int)decoded->variant.device_metrics.uptime_seconds);
} else if (decoded->which_variant == meshtastic_Telemetry_environment_metrics_tag) {
msgPayload["temperature"] = new JSONValue(decoded->variant.environment_metrics.temperature);
msgPayload["relative_humidity"] = new JSONValue(decoded->variant.environment_metrics.relative_humidity);
@@ -710,10 +710,10 @@ std::string MQTT::meshPacketToJson(meshtastic_MeshPacket *mp)
if (pb_decode_from_bytes(mp->decoded.payload.bytes, mp->decoded.payload.size, &meshtastic_Position_msg, &scratch)) {
decoded = &scratch;
if ((int)decoded->time) {
msgPayload["time"] = new JSONValue((uint)decoded->time);
msgPayload["time"] = new JSONValue((unsigned int)decoded->time);
}
if ((int)decoded->timestamp) {
msgPayload["timestamp"] = new JSONValue((uint)decoded->timestamp);
msgPayload["timestamp"] = new JSONValue((unsigned int)decoded->timestamp);
}
msgPayload["latitude_i"] = new JSONValue((int)decoded->latitude_i);
msgPayload["longitude_i"] = new JSONValue((int)decoded->longitude_i);
@@ -721,13 +721,13 @@ std::string MQTT::meshPacketToJson(meshtastic_MeshPacket *mp)
msgPayload["altitude"] = new JSONValue((int)decoded->altitude);
}
if ((int)decoded->ground_speed) {
msgPayload["ground_speed"] = new JSONValue((uint)decoded->ground_speed);
msgPayload["ground_speed"] = new JSONValue((unsigned int)decoded->ground_speed);
}
if (int(decoded->ground_track)) {
msgPayload["ground_track"] = new JSONValue((uint)decoded->ground_track);
msgPayload["ground_track"] = new JSONValue((unsigned int)decoded->ground_track);
}
if (int(decoded->sats_in_view)) {
msgPayload["sats_in_view"] = new JSONValue((uint)decoded->sats_in_view);
msgPayload["sats_in_view"] = new JSONValue((unsigned int)decoded->sats_in_view);
}
if ((int)decoded->PDOP) {
msgPayload["PDOP"] = new JSONValue((int)decoded->PDOP);
@@ -754,11 +754,11 @@ std::string MQTT::meshPacketToJson(meshtastic_MeshPacket *mp)
memset(&scratch, 0, sizeof(scratch));
if (pb_decode_from_bytes(mp->decoded.payload.bytes, mp->decoded.payload.size, &meshtastic_Waypoint_msg, &scratch)) {
decoded = &scratch;
msgPayload["id"] = new JSONValue((uint)decoded->id);
msgPayload["id"] = new JSONValue((unsigned int)decoded->id);
msgPayload["name"] = new JSONValue(decoded->name);
msgPayload["description"] = new JSONValue(decoded->description);
msgPayload["expire"] = new JSONValue((uint)decoded->expire);
msgPayload["locked_to"] = new JSONValue((uint)decoded->locked_to);
msgPayload["expire"] = new JSONValue((unsigned int)decoded->expire);
msgPayload["locked_to"] = new JSONValue((unsigned int)decoded->locked_to);
msgPayload["latitude_i"] = new JSONValue((int)decoded->latitude_i);
msgPayload["longitude_i"] = new JSONValue((int)decoded->longitude_i);
jsonObj["payload"] = new JSONValue(msgPayload);
@@ -775,14 +775,14 @@ std::string MQTT::meshPacketToJson(meshtastic_MeshPacket *mp)
if (pb_decode_from_bytes(mp->decoded.payload.bytes, mp->decoded.payload.size, &meshtastic_NeighborInfo_msg,
&scratch)) {
decoded = &scratch;
msgPayload["node_id"] = new JSONValue((uint)decoded->node_id);
msgPayload["node_broadcast_interval_secs"] = new JSONValue((uint)decoded->node_broadcast_interval_secs);
msgPayload["last_sent_by_id"] = new JSONValue((uint)decoded->last_sent_by_id);
msgPayload["node_id"] = new JSONValue((unsigned int)decoded->node_id);
msgPayload["node_broadcast_interval_secs"] = new JSONValue((unsigned int)decoded->node_broadcast_interval_secs);
msgPayload["last_sent_by_id"] = new JSONValue((unsigned int)decoded->last_sent_by_id);
msgPayload["neighbors_count"] = new JSONValue(decoded->neighbors_count);
JSONArray neighbors;
for (uint8_t i = 0; i < decoded->neighbors_count; i++) {
JSONObject neighborObj;
neighborObj["node_id"] = new JSONValue((uint)decoded->neighbors[i].node_id);
neighborObj["node_id"] = new JSONValue((unsigned int)decoded->neighbors[i].node_id);
neighborObj["snr"] = new JSONValue((int)decoded->neighbors[i].snr);
neighbors.push_back(new JSONValue(neighborObj));
}
@@ -843,9 +843,9 @@ std::string MQTT::meshPacketToJson(meshtastic_MeshPacket *mp)
memset(&scratch, 0, sizeof(scratch));
if (pb_decode_from_bytes(mp->decoded.payload.bytes, mp->decoded.payload.size, &meshtastic_Paxcount_msg, &scratch)) {
decoded = &scratch;
msgPayload["wifi_count"] = new JSONValue((uint)decoded->wifi);
msgPayload["ble_count"] = new JSONValue((uint)decoded->ble);
msgPayload["uptime"] = new JSONValue((uint)decoded->uptime);
msgPayload["wifi_count"] = new JSONValue((unsigned int)decoded->wifi);
msgPayload["ble_count"] = new JSONValue((unsigned int)decoded->ble);
msgPayload["uptime"] = new JSONValue((unsigned int)decoded->uptime);
jsonObj["payload"] = new JSONValue(msgPayload);
} else {
LOG_ERROR("Error decoding protobuf for Paxcount message!\n");
@@ -862,12 +862,12 @@ std::string MQTT::meshPacketToJson(meshtastic_MeshPacket *mp)
decoded = &scratch;
if (decoded->type == meshtastic_HardwareMessage_Type_GPIOS_CHANGED) {
msgType = "gpios_changed";
msgPayload["gpio_value"] = new JSONValue((uint)decoded->gpio_value);
msgPayload["gpio_value"] = new JSONValue((unsigned int)decoded->gpio_value);
jsonObj["payload"] = new JSONValue(msgPayload);
} else if (decoded->type == meshtastic_HardwareMessage_Type_READ_GPIOS_REPLY) {
msgType = "gpios_read_reply";
msgPayload["gpio_value"] = new JSONValue((uint)decoded->gpio_value);
msgPayload["gpio_mask"] = new JSONValue((uint)decoded->gpio_mask);
msgPayload["gpio_value"] = new JSONValue((unsigned int)decoded->gpio_value);
msgPayload["gpio_mask"] = new JSONValue((unsigned int)decoded->gpio_mask);
jsonObj["payload"] = new JSONValue(msgPayload);
}
} else {
@@ -883,11 +883,11 @@ std::string MQTT::meshPacketToJson(meshtastic_MeshPacket *mp)
LOG_WARN("Couldn't convert encrypted payload of MeshPacket to JSON\n");
}
jsonObj["id"] = new JSONValue((uint)mp->id);
jsonObj["timestamp"] = new JSONValue((uint)mp->rx_time);
jsonObj["to"] = new JSONValue((uint)mp->to);
jsonObj["from"] = new JSONValue((uint)mp->from);
jsonObj["channel"] = new JSONValue((uint)mp->channel);
jsonObj["id"] = new JSONValue((unsigned int)mp->id);
jsonObj["timestamp"] = new JSONValue((unsigned int)mp->rx_time);
jsonObj["to"] = new JSONValue((unsigned int)mp->to);
jsonObj["from"] = new JSONValue((unsigned int)mp->from);
jsonObj["channel"] = new JSONValue((unsigned int)mp->channel);
jsonObj["type"] = new JSONValue(msgType.c_str());
jsonObj["sender"] = new JSONValue(owner.id);
if (mp->rx_rssi != 0)
@@ -895,7 +895,7 @@ std::string MQTT::meshPacketToJson(meshtastic_MeshPacket *mp)
if (mp->rx_snr != 0)
jsonObj["snr"] = new JSONValue((float)mp->rx_snr);
if (mp->hop_start != 0 && mp->hop_limit <= mp->hop_start)
jsonObj["hops_away"] = new JSONValue((uint)(mp->hop_start - mp->hop_limit));
jsonObj["hops_away"] = new JSONValue((unsigned int)(mp->hop_start - mp->hop_limit));
// serialize and write it to the stream
JSONValue *value = new JSONValue(jsonObj);

View File

@@ -143,6 +143,8 @@
#define HW_VENDOR meshtastic_HardwareModel_STATION_G2
#elif defined(UNPHONE)
#define HW_VENDOR meshtastic_HardwareModel_UNPHONE
#elif defined(WIPHONE)
#define HW_VENDOR meshtastic_HardwareModel_WIPHONE
#endif
// -----------------------------------------------------------------------------

View File

@@ -287,7 +287,7 @@ void NRF52Bluetooth::setup()
LOG_INFO("Advertising\n");
}
void NRF52Bluetooth::resumeAdverising()
void NRF52Bluetooth::resumeAdvertising()
{
Bluefruit.Advertising.restartOnDisconnect(true);
Bluefruit.Advertising.setInterval(32, 244); // in unit of 0.625 ms

View File

@@ -8,7 +8,7 @@ class NRF52Bluetooth : BluetoothApi
public:
void setup();
void shutdown();
void resumeAdverising();
void resumeAdvertising();
void clearBonds();
bool isConnected();
int getRssi();

View File

@@ -54,6 +54,8 @@
#define HW_VENDOR meshtastic_HardwareModel_NRF52840_PCA10059
#elif defined(TWC_MESH_V4)
#define HW_VENDOR meshtastic_HardwareModel_TWC_MESH_V4
#elif defined(NRF52_PROMICRO_DIY)
#define HW_VENDOR meshtastic_HardwareModel_NRF52_PROMICRO_DIY
#elif defined(PRIVATE_HW) || defined(FEATHER_DIY)
#define HW_VENDOR meshtastic_HardwareModel_PRIVATE_HW
#else

View File

@@ -80,7 +80,7 @@ void setBluetoothEnable(bool enable)
// We delay brownout init until after BLE because BLE starts soft device
initBrownout();
} else {
nrf52Bluetooth->resumeAdverising();
nrf52Bluetooth->resumeAdvertising();
}
}
} else {

View File

@@ -75,20 +75,20 @@ void portduinoSetup()
{
printf("Setting up Meshtastic on Portduino...\n");
int max_GPIO = 0;
configNames GPIO_lines[] = {cs,
irq,
busy,
reset,
txen,
rxen,
displayDC,
displayCS,
displayBacklight,
displayBacklightPWMChannel,
displayReset,
touchscreenCS,
touchscreenIRQ,
user};
const configNames GPIO_lines[] = {cs,
irq,
busy,
reset,
txen,
rxen,
displayDC,
displayCS,
displayBacklight,
displayBacklightPWMChannel,
displayReset,
touchscreenCS,
touchscreenIRQ,
user};
std::string gpioChipName = "gpiochip";
settingsStrings[i2cdev] = "";
@@ -103,7 +103,7 @@ void portduinoSetup()
std::cout << "Using " << configPath << " as config file" << std::endl;
try {
yamlConfig = YAML::LoadFile(configPath);
} catch (YAML::Exception e) {
} catch (YAML::Exception &e) {
std::cout << "Could not open " << configPath << " because of error: " << e.what() << std::endl;
exit(EXIT_FAILURE);
}
@@ -111,7 +111,7 @@ void portduinoSetup()
std::cout << "Using local config.yaml as config file" << std::endl;
try {
yamlConfig = YAML::LoadFile("config.yaml");
} catch (YAML::Exception e) {
} catch (YAML::Exception &e) {
std::cout << "*** Exception " << e.what() << std::endl;
exit(EXIT_FAILURE);
}
@@ -119,7 +119,7 @@ void portduinoSetup()
std::cout << "Using /etc/meshtasticd/config.yaml as config file" << std::endl;
try {
yamlConfig = YAML::LoadFile("/etc/meshtasticd/config.yaml");
} catch (YAML::Exception e) {
} catch (YAML::Exception &e) {
std::cout << "*** Exception " << e.what() << std::endl;
exit(EXIT_FAILURE);
}
@@ -168,6 +168,7 @@ void portduinoSetup()
settingsMap[txen] = yamlConfig["Lora"]["TXen"].as<int>(RADIOLIB_NC);
settingsMap[rxen] = yamlConfig["Lora"]["RXen"].as<int>(RADIOLIB_NC);
settingsMap[gpiochip] = yamlConfig["Lora"]["gpiochip"].as<int>(0);
settingsMap[ch341Quirk] = yamlConfig["Lora"]["ch341_quirk"].as<bool>(false);
gpioChipName += std::to_string(settingsMap[gpiochip]);
settingsStrings[spidev] = "/dev/" + yamlConfig["Lora"]["spidev"].as<std::string>("spidev0.0");
@@ -276,7 +277,7 @@ void portduinoSetup()
settingsMap[maxnodes] = (yamlConfig["General"]["MaxNodes"]).as<int>(200);
} catch (YAML::Exception e) {
} catch (YAML::Exception &e) {
std::cout << "*** Exception " << e.what() << std::endl;
exit(EXIT_FAILURE);
}
@@ -347,7 +348,7 @@ void portduinoSetup()
return;
}
int initGPIOPin(int pinNum, std::string gpioChipName)
int initGPIOPin(int pinNum, const std::string gpioChipName)
{
std::string gpio_name = "GPIO" + std::to_string(pinNum);
try {

View File

@@ -11,6 +11,7 @@ enum configNames {
rxen,
dio2_as_rf_switch,
dio3_tcxo_voltage,
ch341Quirk,
use_rf95,
use_sx1280,
use_sx1268,

View File

@@ -186,9 +186,9 @@ int File::available(void)
_fs->_lockFS();
if (!this->_is_dir) {
uint32_t size = lfs_file_size(_fs->_getFS(), _file);
uint32_t fsize = lfs_file_size(_fs->_getFS(), _file);
uint32_t pos = lfs_file_tell(_fs->_getFS(), _file);
ret = size - pos;
ret = fsize - pos;
}
_fs->_unlockFS();

View File

@@ -1,6 +1,7 @@
#pragma once
#include "PowerStatus.h"
#include "concurrency/OSThread.h"
#include "configuration.h"
#ifdef ARCH_ESP32
#include <esp_adc_cal.h>
#include <soc/adc_channel.h>
@@ -36,7 +37,7 @@ extern RTC_NOINIT_ATTR uint64_t RTC_reg_b;
#include "soc/sens_reg.h" // needed for adc pin reset
#endif
#if HAS_TELEMETRY && !defined(ARCH_PORTDUINO)
#if HAS_TELEMETRY && !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR && !defined(ARCH_PORTDUINO)
#include "modules/Telemetry/Sensor/INA219Sensor.h"
#include "modules/Telemetry/Sensor/INA260Sensor.h"
#include "modules/Telemetry/Sensor/INA3221Sensor.h"

View File

@@ -0,0 +1,31 @@
/*
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[] = {
// P0
0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31,
// P1
32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47};

View File

@@ -0,0 +1,154 @@
#ifndef _VARIANT_PROMICRO_DIY_
#define _VARIANT_PROMICRO_DIY_
/** Master clock frequency */
#define VARIANT_MCK (64000000ul)
// #define USE_LFXO // Board uses 32khz crystal for LF
#define USE_LFRC // Board uses RC for LF
#define PROMICRO_DIY_TCXO
/*----------------------------------------------------------------------------
* Headers
*----------------------------------------------------------------------------*/
#include "WVariant.h"
#ifdef __cplusplus
extern "C" {
#endif // __cplusplus
/*
NRF52 PRO MICRO PIN ASSIGNMENT
| Pin | Function | | Pin | Function |
|-------|------------|---|---------|-------------|
| Gnd | | | vbat | |
| P0.06 | Serial2 RX | | vbat | |
| P0.08 | Serial2 TX | | Gnd | |
| Gnd | | | reset | |
| Gnd | | | ext_vcc | *see 0.13 |
| P0.17 | RXEN | | P0.31 | BATTERY_PIN |
| P0.20 | GPS_RX | | P0.29 | BUSY |
| P0.22 | GPS_TX | | P0.02 | MISO |
| P0.24 | GPS_EN | | P1.15 | MOSI |
| P1.00 | BUTTON_PIN | | P1.13 | CS |
| P0.11 | SCL | | P1.11 | SCK |
| P1.04 | SDA | | P0.10 | DIO1/IRQ |
| P1.06 | Free pin | | P0.09 | RESET |
| | | | | |
| | Mid board | | | Internal |
| P1.01 | Free pin | | 0.15 | LED |
| P1.02 | Free pin | | 0.13 | 3V3_EN |
| P1.07 | Free pin | | | |
*/
// Number of pins defined in PinDescription array
#define PINS_COUNT (48)
#define NUM_DIGITAL_PINS (48)
#define NUM_ANALOG_INPUTS (1)
#define NUM_ANALOG_OUTPUTS (0)
// Pin 13 enables 3.3V periphery. If the Lora module is on this pin, then it should stay enabled at all times.
#define PIN_3V3_EN (0 + 13) // P0.13
// Analog pins
#define BATTERY_PIN (0 + 31) // P0.31 Battery ADC
#define ADC_CHANNEL ADC1_GPIO4_CHANNEL
#define ADC_RESOLUTION 14
#define BATTERY_SENSE_RESOLUTION_BITS 12
#define BATTERY_SENSE_RESOLUTION 4096.0
// Definition of milliVolt per LSB => 3.0V ADC range and 12-bit ADC resolution = 3000mV/4096
#define VBAT_MV_PER_LSB (0.73242188F)
// Voltage divider value => 1.5M + 1M voltage divider on VBAT = (1.5M / (1M + 1.5M))
#define VBAT_DIVIDER (0.6F)
// Compensation factor for the VBAT divider
#define VBAT_DIVIDER_COMP (1.73)
// Fixed calculation of milliVolt from compensation value
#define REAL_VBAT_MV_PER_LSB (VBAT_DIVIDER_COMP * VBAT_MV_PER_LSB)
#undef AREF_VOLTAGE
#define AREF_VOLTAGE 3.0
#define VBAT_AR_INTERNAL AR_INTERNAL_3_0
#define ADC_MULTIPLIER VBAT_DIVIDER_COMP // REAL_VBAT_MV_PER_LSB
#define VBAT_RAW_TO_SCALED(x) (REAL_VBAT_MV_PER_LSB * x)
// WIRE IC AND IIC PINS
#define WIRE_INTERFACES_COUNT 1
#define PIN_WIRE_SDA (32 + 4) // P1.04
#define PIN_WIRE_SCL (0 + 11) // P0.11
// LED
#define PIN_LED1 (0 + 15) // P0.15
#define LED_BUILTIN PIN_LED1
// Actually red
#define LED_BLUE PIN_LED1
#define LED_STATE_ON 1 // State when LED is lit
// Button
#define BUTTON_PIN (32 + 0) // P1.00
// GPS
#define PIN_GPS_TX (0 + 22) // P0.22
#define PIN_GPS_RX (0 + 20) // P0.20
#define PIN_GPS_EN (0 + 24) // P0.24
#define GPS_POWER_TOGGLE
#define GPS_UBLOX
// define GPS_DEBUG
// UART interfaces
#define PIN_SERIAL1_RX PIN_GPS_TX
#define PIN_SERIAL1_TX PIN_GPS_RX
#define PIN_SERIAL2_RX (0 + 6) // P0.06
#define PIN_SERIAL2_TX (0 + 8) // P0.08
// Serial interfaces
#define SPI_INTERFACES_COUNT 1
#define PIN_SPI_MISO (0 + 2) // P0.02
#define PIN_SPI_MOSI (32 + 15) // P1.15
#define PIN_SPI_SCK (32 + 11) // P1.11
// LORA MODULES
#define USE_LLCC68
#define USE_SX1262
// LORA CONFIG
#define SX126X_CS (32 + 13) // P1.13 FIXME - we really should define LORA_CS instead
#define SX126X_DIO1 (0 + 10) // P0.10 IRQ
#define SX126X_DIO2_AS_RF_SWITCH // Note for E22 modules: DIO2 is not attached internally to TXEN for automatic TX/RX switching,
// so it needs connecting externally if it is used in this way
#define SX126X_BUSY (0 + 29) // P0.29
#define SX126X_RESET (0 + 9) // P0.09
#define SX126X_RXEN (0 + 17) // P0.17
#define SX126X_TXEN RADIOLIB_NC // Assuming that DIO2 is connected to TXEN pin. If not, TXEN must be connected.
/*
On the SX1262, DIO3 sets the voltage for an external TCXO, if one is present. If one is not present, then this should not be used.
Ebyte
e22-900mm22s has no TCXO
e22-900m22s has TCXO
e220-900mm22s has no TCXO, works with/without this definition, looks like DIO3 not connected at all
AI-thinker
RA-01SH does not have TCXO
Waveshare
Core1262 has TCXO
*/
#define SX126X_DIO3_TCXO_VOLTAGE 1.8
#ifdef __cplusplus
}
#endif
/*----------------------------------------------------------------------------
* Arduino objects - C++ only
*----------------------------------------------------------------------------*/
#endif

View File

@@ -0,0 +1,31 @@
/*
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[] = {
// P0
0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31,
// P1
32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47};

View File

@@ -0,0 +1,153 @@
#ifndef _VARIANT_PROMICRO_DIY_
#define _VARIANT_PROMICRO_DIY_
/** Master clock frequency */
#define VARIANT_MCK (64000000ul)
// #define USE_LFXO // Board uses 32khz crystal for LF
#define USE_LFRC // Board uses RC for LF
#define PROMICRO_DIY_XTAL
/*----------------------------------------------------------------------------
* Headers
*----------------------------------------------------------------------------*/
#include "WVariant.h"
#ifdef __cplusplus
extern "C" {
#endif // __cplusplus
/*
NRF52 PRO MICRO PIN ASSIGNMENT
| Pin | Function | | Pin | Function |
|-------|------------|---|---------|-------------|
| Gnd | | | vbat | |
| P0.06 | Serial2 RX | | vbat | |
| P0.08 | Serial2 TX | | Gnd | |
| Gnd | | | reset | |
| Gnd | | | ext_vcc | *see 0.13 |
| P0.17 | RXEN | | P0.31 | BATTERY_PIN |
| P0.20 | GPS_RX | | P0.29 | BUSY |
| P0.22 | GPS_TX | | P0.02 | MISO |
| P0.24 | GPS_EN | | P1.15 | MOSI |
| P1.00 | BUTTON_PIN | | P1.13 | CS |
| P0.11 | SCL | | P1.11 | SCK |
| P1.04 | SDA | | P0.10 | DIO1/IRQ |
| P1.06 | Free pin | | P0.09 | RESET |
| | | | | |
| | Mid board | | | Internal |
| P1.01 | Free pin | | 0.15 | LED |
| P1.02 | Free pin | | 0.13 | 3V3_EN |
| P1.07 | Free pin | | | |
*/
// Number of pins defined in PinDescription array
#define PINS_COUNT (48)
#define NUM_DIGITAL_PINS (48)
#define NUM_ANALOG_INPUTS (1)
#define NUM_ANALOG_OUTPUTS (0)
// Pin 13 enables 3.3V periphery. If the Lora module is on this pin, then it should stay enabled at all times.
#define PIN_3V3_EN (0 + 13) // P0.13
// Analog pins
#define BATTERY_PIN (0 + 31) // P0.31 Battery ADC
#define ADC_CHANNEL ADC1_GPIO4_CHANNEL
#define ADC_RESOLUTION 14
#define BATTERY_SENSE_RESOLUTION_BITS 12
#define BATTERY_SENSE_RESOLUTION 4096.0
// Definition of milliVolt per LSB => 3.0V ADC range and 12-bit ADC resolution = 3000mV/4096
#define VBAT_MV_PER_LSB (0.73242188F)
// Voltage divider value => 1.5M + 1M voltage divider on VBAT = (1.5M / (1M + 1.5M))
#define VBAT_DIVIDER (0.6F)
// Compensation factor for the VBAT divider
#define VBAT_DIVIDER_COMP (1.73)
// Fixed calculation of milliVolt from compensation value
#define REAL_VBAT_MV_PER_LSB (VBAT_DIVIDER_COMP * VBAT_MV_PER_LSB)
#undef AREF_VOLTAGE
#define AREF_VOLTAGE 3.0
#define VBAT_AR_INTERNAL AR_INTERNAL_3_0
#define ADC_MULTIPLIER VBAT_DIVIDER_COMP // REAL_VBAT_MV_PER_LSB
#define VBAT_RAW_TO_SCALED(x) (REAL_VBAT_MV_PER_LSB * x)
// WIRE IC AND IIC PINS
#define WIRE_INTERFACES_COUNT 1
#define PIN_WIRE_SDA (32 + 4) // P1.04
#define PIN_WIRE_SCL (0 + 11) // P0.11
// LED
#define PIN_LED1 (0 + 15) // P0.15
#define LED_BUILTIN PIN_LED1
// Actually red
#define LED_BLUE PIN_LED1
#define LED_STATE_ON 1 // State when LED is lit
// Button
#define BUTTON_PIN (32 + 0) // P1.00
// GPS
#define PIN_GPS_TX (0 + 22) // P0.22
#define PIN_GPS_RX (0 + 20) // P0.20
#define PIN_GPS_EN (0 + 24) // P0.24
#define GPS_POWER_TOGGLE
#define GPS_UBLOX
// define GPS_DEBUG
// UART interfaces
#define PIN_SERIAL1_RX PIN_GPS_TX
#define PIN_SERIAL1_TX PIN_GPS_RX
#define PIN_SERIAL2_RX (0 + 6) // P0.06
#define PIN_SERIAL2_TX (0 + 8) // P0.08
// Serial interfaces
#define SPI_INTERFACES_COUNT 1
#define PIN_SPI_MISO (0 + 2) // P0.02
#define PIN_SPI_MOSI (32 + 15) // P1.15
#define PIN_SPI_SCK (32 + 11) // P1.11
// LORA MODULES
#define USE_LLCC68
#define USE_SX1262
// LORA CONFIG
#define SX126X_CS (32 + 13) // P1.13 FIXME - we really should define LORA_CS instead
#define SX126X_DIO1 (0 + 10) // P0.10 IRQ
#define SX126X_DIO2_AS_RF_SWITCH // Note for E22 modules: DIO2 is not attached internally to TXEN for automatic TX/RX switching,
// so it needs connecting externally if it is used in this way
#define SX126X_BUSY (0 + 29) // P0.29
#define SX126X_RESET (0 + 9) // P0.09
#define SX126X_RXEN (0 + 17) // P0.17
#define SX126X_TXEN RADIOLIB_NC // Assuming that DIO2 is connected to TXEN pin. If not, TXEN must be connected.
/*
On the SX1262, DIO3 sets the voltage for an external TCXO, if one is present. If one is not present, then this should not be used.
Ebyte
e22-900mm22s has no TCXO
e22-900m22s has TCXO
e220-900mm22s has no TCXO, works with/without this definition, looks like DIO3 not connected at all
AI-thinker
RA-01SH does not have TCXO
Waveshare
Core1262 has TCXO
*/
// #define SX126X_DIO3_TCXO_VOLTAGE 1.8
#ifdef __cplusplus
}
#endif
/*----------------------------------------------------------------------------
* Arduino objects - C++ only
*----------------------------------------------------------------------------*/
#endif

View File

@@ -44,3 +44,35 @@ build_flags =
${esp32_base.build_flags}
-D DIY_V1
-I variants/diy/hydra
; Promicro + E22(0)-xxxMM / RA-01SH modules board variant - DIY - without TCXO
[env:nrf52_promicro_diy_xtal]
extends = nrf52840_base
board = promicro-nrf52840
board_level = extra
build_flags = ${nrf52840_base.build_flags}
-I variants/diy/nrf52_promicro_diy_xtal
-D NRF52_PROMICRO_DIY
-D OLED_RU
-L "${platformio.libdeps_dir}/${this.__env__}/BSEC2 Software Library/src/cortex-m4/fpv4-sp-d16-hard"
build_src_filter = ${nrf52_base.build_src_filter} +<../variants/diy/nrf52_promicro_diy_xtal>
lib_deps =
${nrf52840_base.lib_deps}
debug_tool = jlink
; Promicro + E22(0)-xxxM / HT-RA62 modules board variant - DIY - with TCXO
[env:nrf52_promicro_diy_tcxo]
extends = nrf52840_base
board = promicro-nrf52840
board_level = extra
build_flags = ${nrf52840_base.build_flags}
-I variants/diy/nrf52_promicro_diy_tcxo
-D NRF52_PROMICRO_DIY
-D OLED_RU
-L "${platformio.libdeps_dir}/${this.__env__}/BSEC2 Software Library/src/cortex-m4/fpv4-sp-d16-hard"
build_src_filter = ${nrf52_base.build_src_filter} +<../variants/diy/nrf52_promicro_diy_tcxo>
lib_deps =
${nrf52840_base.lib_deps}
debug_tool = jlink

View File

@@ -18,6 +18,7 @@
#define TFT_OFFSET_ROTATION 0
#define SCREEN_ROTATE
#define SCREEN_TRANSITION_FRAMERATE 5
#define BRIGHTNESS_DEFAULT 130 // Medium Low Brightness
#define HAS_TOUCHSCREEN 1
#define SCREEN_TOUCH_INT 16
@@ -96,4 +97,4 @@
#define SX126X_DIO2_AS_RF_SWITCH
#define SX126X_DIO3_TCXO_VOLTAGE 1.8
// Internally the TTGO module hooks the SX1262-DIO2 in to control the TX/RX switch (which is the default for the sx1262interface
// code)
// code)

View File

@@ -15,7 +15,7 @@ build_flags = ${nrf52840_base.build_flags} -Ivariants/t-echo
-DEINK_LIMIT_FASTREFRESH=20 ; How many consecutive fast-refreshes are permitted
-DEINK_LIMIT_RATE_BACKGROUND_SEC=30 ; Minimum interval between BACKGROUND updates
-DEINK_LIMIT_RATE_RESPONSIVE_SEC=1 ; Minimum interval between RESPONSIVE updates
-DEINK_LIMIT_GHOSTING_PX=2000 ; (Optional) How much image ghosting is tolerated
; -DEINK_LIMIT_GHOSTING_PX=2000 ; (Optional) How much image ghosting is tolerated
-DEINK_BACKGROUND_USES_FAST ; (Optional) Use FAST refresh for both BACKGROUND and RESPONSIVE, until a limit is reached.
build_src_filter = ${nrf52_base.build_src_filter} +<../variants/t-echo>
lib_deps =

View File

@@ -65,6 +65,9 @@ extern "C" {
#define PIN_BUTTON2 (0 + 18) // 0.18 is labeled on the board as RESET but we configure it in the bootloader as a regular GPIO
#define PIN_BUTTON_TOUCH (0 + 11) // 0.11 is the soft touch button on T-Echo
#define BUTTON_CLICK_MS 400
#define BUTTON_TOUCH_MS 200
/*
* Analog pins
*/

View File

@@ -3,8 +3,6 @@
extends = esp32s3_base
board = tbeam-s3-core
platform_packages = framework-arduinoespressif32 @ https://github.com/espressif/arduino-esp32.git#2.0.15
lib_deps =
${esp32s3_base.lib_deps}
lewisxhe/PCF8563_Library@1.0.1

View File

@@ -0,0 +1,52 @@
#ifndef Pins_Arduino_h
#define Pins_Arduino_h
#include <stdint.h>
#define EXTERNAL_NUM_INTERRUPTS 16
#define NUM_DIGITAL_PINS 20
#define NUM_ANALOG_INPUTS 16
#define analogInputToDigitalPin(p) (((p) < 20) ? (esp32_adc2gpio[(p)]) : -1)
#define digitalPinToInterrupt(p) (((p) < 40) ? (p) : -1)
#define digitalPinHasPWM(p) (p < 34)
static const uint8_t TX = 1;
static const uint8_t RX = 3;
static const uint8_t SDA = 21;
static const uint8_t SCL = 22;
static const uint8_t SS = 5;
static const uint8_t MOSI = 23;
static const uint8_t MISO = 19;
static const uint8_t SCK = 18;
static const uint8_t G23 = 23;
static const uint8_t G19 = 19;
static const uint8_t G18 = 18;
static const uint8_t G3 = 3;
static const uint8_t G16 = 16;
static const uint8_t G21 = 21;
static const uint8_t G2 = 2;
static const uint8_t G12 = 12;
static const uint8_t G15 = 15;
static const uint8_t G35 = 35;
static const uint8_t G36 = 36;
static const uint8_t G25 = 25;
static const uint8_t G26 = 26;
static const uint8_t G1 = 1;
static const uint8_t G17 = 17;
static const uint8_t G22 = 22;
static const uint8_t G5 = 5;
static const uint8_t G13 = 13;
static const uint8_t G0 = 0;
static const uint8_t G34 = 34;
static const uint8_t DAC1 = 25;
static const uint8_t DAC2 = 26;
static const uint8_t ADC1 = 35;
static const uint8_t ADC2 = 36;
#endif /* Pins_Arduino_h */

View File

@@ -0,0 +1,13 @@
[env:wiphone]
extends = esp32_base
board = wiphone
monitor_filters = esp32_exception_decoder
board_build.partitions = default_16MB.csv
build_flags =
${esp32_base.build_flags} -D WIPHONE -I variants/wiphone
lib_deps =
${esp32_base.lib_deps}
lovyan03/LovyanGFX@^1.1.8
sparkfun/SX1509 IO Expander@^3.0.5
pololu/APA102@^3.0.0

View File

@@ -0,0 +1,58 @@
#define I2C_SDA 15
#define I2C_SCL 25
#define GPIO_EXTENDER 1509
#define EXTENDER_FLAG 0x40
#define EXTENDER_PIN(x) (x + EXTENDER_FLAG)
#undef RF95_SCK
#undef RF95_MISO
#undef RF95_MOSI
#undef RF95_NSS
#define RF95_SCK 14
#define RF95_MISO 12
#define RF95_MOSI 13
#define RF95_NSS 27
#define USE_RF95
#define LORA_DIO0 38
#define LORA_RESET RADIOLIB_NC
#define LORA_DIO1 RADIOLIB_NC
#define LORA_DIO2 RADIOLIB_NC
// This board has no GPS or Screen for now
#undef GPS_RX_PIN
#undef GPS_TX_PIN
#define NO_GPS
#define HAS_GPS 0
#define NO_SCREEN
#define HAS_SCREEN 0
// Default SPI1 will be mapped to the display
#define ST7789_SDA 23
#define ST7789_SCK 18
#define ST7789_CS 5
#define ST7789_RS 26
#define ST7789_BL -1 // EXTENDER_PIN(9)
#define ST7789_RESET -1
#define ST7789_MISO 19
#define ST7789_BUSY -1
#define ST7789_SPI_HOST SPI3_HOST
#define ST7789_BACKLIGHT_EN -1 // EXTENDER_PIN(9)
#define SPI_FREQUENCY 40000000
#define SPI_READ_FREQUENCY 16000000
#define TFT_HEIGHT 240
#define TFT_WIDTH 320
#define TFT_OFFSET_X 0
#define TFT_OFFSET_Y 0
#define TFT_OFFSET_ROTATION 0
#define SCREEN_ROTATE
#define SCREEN_TRANSITION_FRAMERATE 5
#define I2S_MCLK_GPIO0
#define I2S_BCK_PIN 4 // rev1.3 - 4 (wp05)
#define I2S_WS_PIN 33
#define I2S_MOSI_PIN 21
#define I2S_MISO_PIN 34

View File

@@ -1,4 +1,4 @@
[VERSION]
major = 2
minor = 3
build = 8
build = 9