Merge branch 'master' into tft-gui-work

pull/3259/head
Manuel 2024-05-04 09:11:56 +02:00 zatwierdzone przez GitHub
commit 1ec40f29d8
Nie znaleziono w bazie danych klucza dla tego podpisu
ID klucza GPG: B5690EEEBB952194
65 zmienionych plików z 452 dodań i 148 usunięć

Wyświetl plik

@ -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 = release
build_flags =
${arduino_base.build_flags}
-DSERIAL_BUFFER_SIZE=1024

Wyświetl plik

@ -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,5 @@ 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

Wyświetl plik

@ -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

Wyświetl plik

@ -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

Wyświetl plik

@ -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) {

Wyświetl plik

@ -2,6 +2,7 @@
#include "NodeDB.h"
#include "PowerFSM.h"
#include "configuration.h"
#include "time.h"
#ifdef RP2040_SLOW_CLOCK
#define Port Serial2

Wyświetl plik

@ -128,6 +128,7 @@ along with this program. If not, see <http://www.gnu.org/licenses/>.
#define LPS22HB_ADDR_ALT 0x5D
#define SHT31_ADDR 0x44
#define PMSA0031_ADDR 0x12
#define RCWL9620_ADDR 0x57
// -----------------------------------------------------------------------------
// ACCELEROMETER

Wyświetl plik

@ -41,6 +41,7 @@ class ScanI2C
BQ24295,
LSM6DS3,
TCA9555,
RCWL9620,
NCP5623,
} DeviceType;

Wyświetl plik

@ -294,6 +294,7 @@ void ScanI2CTwoWire::scanPort(I2CPort port)
SCAN_SIMPLE_CASE(SHT31_ADDR, SHT31, "SHT31 sensor found\n")
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")

Wyświetl plik

@ -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();

Wyświetl plik

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

Wyświetl plik

@ -212,7 +212,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);
@ -556,6 +558,7 @@ 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)
i2cScanner.reset();
@ -622,7 +625,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;

Wyświetl plik

@ -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

Wyświetl plik

@ -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;
@ -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++) {

Wyświetl plik

@ -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();

Wyświetl plik

@ -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 {

Wyświetl plik

@ -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 =

Wyświetl plik

@ -431,14 +431,15 @@ int32_t CannedMessageModule::runOnce()
runState = CANNED_MESSAGE_RUN_STATE_INACTIVE;
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;
// mute (switch off/toggle) external notifications on fn+m
case 0xac:
if (moduleConfig.external_notification.enabled == true) {

Wyświetl plik

@ -146,7 +146,7 @@ void setupModules()
new AirQualityTelemetryModule();
}
#endif
#if HAS_TELEMETRY && !defined(ARCH_PORTDUINO) && !MESHTASTIC_EXCLUDE_POWER_TELEMETRY
#if HAS_TELEMETRY && !defined(ARCH_PORTDUINO) && !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) && \

Wyświetl plik

@ -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);
}

Wyświetl plik

@ -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(

Wyświetl plik

@ -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

Wyświetl plik

@ -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

Wyświetl plik

@ -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,6 +24,7 @@
#include "Sensor/BMP280Sensor.h"
#include "Sensor/LPS22HBSensor.h"
#include "Sensor/MCP9808Sensor.h"
#include "Sensor/RCWL9620Sensor.h"
#include "Sensor/SHT31Sensor.h"
#include "Sensor/SHTC3Sensor.h"
@ -32,6 +36,7 @@ MCP9808Sensor mcp9808Sensor;
SHTC3Sensor shtc3Sensor;
LPS22HBSensor lps22hbSensor;
SHT31Sensor sht31Sensor;
RCWL9620Sensor rcwl9620Sensor;
#define FAILED_STATE_SENSOR_READ_MULTIPLIER 10
#define DISPLAY_RECEIVEID_MEASUREMENTS_ON_SCREEN true
@ -90,6 +95,8 @@ int32_t EnvironmentTelemetryModule::runOnce()
result = ina219Sensor.runOnce();
if (ina260Sensor.hasSensor())
result = ina260Sensor.runOnce();
if (rcwl9620Sensor.hasSensor())
result = rcwl9620Sensor.runOnce();
}
return result;
} else {
@ -183,6 +190,9 @@ void EnvironmentTelemetryModule::drawFrame(OLEDDisplay *display, OLEDDisplayUiSt
String(lastMeasurement.variant.environment_metrics.current, 0) + "mA");
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 +202,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,6 +233,8 @@ 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);
@ -241,13 +256,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 +296,6 @@ bool EnvironmentTelemetryModule::sendTelemetry(NodeNum dest, bool phoneOnly)
}
}
return valid;
}
}
#endif

Wyświetl plik

@ -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

Wyświetl plik

@ -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

Wyświetl plik

@ -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

Wyświetl plik

@ -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

Wyświetl plik

@ -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

Wyświetl plik

@ -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

Wyświetl plik

@ -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

Wyświetl plik

@ -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

Wyświetl plik

@ -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

Wyświetl plik

@ -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

Wyświetl plik

@ -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

Wyświetl plik

@ -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

Wyświetl plik

@ -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

Wyświetl plik

@ -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

Wyświetl plik

@ -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

Wyświetl plik

@ -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

Wyświetl plik

@ -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

Wyświetl plik

@ -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

Wyświetl plik

@ -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

Wyświetl plik

@ -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

Wyświetl plik

@ -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

Wyświetl plik

@ -0,0 +1,60 @@
#include "RCWL9620Sensor.h"
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "TelemetrySensor.h"
#include "configuration.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;
}
}

Wyświetl plik

@ -0,0 +1,23 @@
#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;
};

Wyświetl plik

@ -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

Wyświetl plik

@ -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

Wyświetl plik

@ -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

Wyświetl plik

@ -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

Wyświetl plik

@ -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

Wyświetl plik

@ -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

Wyświetl plik

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

Wyświetl plik

@ -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

Wyświetl plik

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

Wyświetl plik

@ -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;

Wyświetl plik

@ -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);

Wyświetl plik

@ -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);

Wyświetl plik

@ -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

Wyświetl plik

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

Wyświetl plik

@ -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 {

Wyświetl plik

@ -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);
}
@ -276,7 +276,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 +347,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 {

Wyświetl plik

@ -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();

Wyświetl plik

@ -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"