mirror of
https://github.com/meshtastic/firmware.git
synced 2025-04-22 16:56:53 +00:00
Very WIP attempt to get Native Sensors working.
This commit is contained in:
parent
da3187e12d
commit
1d8792b282
@ -15,15 +15,13 @@ build_src_filter =
|
||||
+<mesh/raspihttp/>
|
||||
-<mesh/eth/>
|
||||
-<modules/esp32>
|
||||
-<modules/Telemetry/EnvironmentTelemetry.cpp>
|
||||
-<modules/Telemetry/AirQualityTelemetry.cpp>
|
||||
-<modules/Telemetry/Sensor>
|
||||
+<../variants/portduino>
|
||||
|
||||
lib_deps =
|
||||
${env.lib_deps}
|
||||
${networking_base.lib_deps}
|
||||
${radiolib_base.lib_deps}
|
||||
${environmental_base.lib_deps}
|
||||
rweather/Crypto@^0.4.0
|
||||
lovyan03/LovyanGFX@^1.2.0
|
||||
https://github.com/pine64/libch341-spi-userspace#a9b17e3452f7fb747000d9b4ad4409155b39f6ef
|
||||
|
@ -71,14 +71,14 @@ static const uint8_t ext_chrg_detect_value = EXT_CHRG_DETECT_VALUE;
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if HAS_TELEMETRY && !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR && !defined(ARCH_PORTDUINO)
|
||||
#if HAS_TELEMETRY && !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
|
||||
INA219Sensor ina219Sensor;
|
||||
INA226Sensor ina226Sensor;
|
||||
INA260Sensor ina260Sensor;
|
||||
INA3221Sensor ina3221Sensor;
|
||||
#endif
|
||||
|
||||
#if !MESHTASTIC_EXCLUDE_I2C && !defined(ARCH_PORTDUINO) && !defined(ARCH_STM32WL)
|
||||
#if !MESHTASTIC_EXCLUDE_I2C && !defined(ARCH_STM32WL)
|
||||
#include "modules/Telemetry/Sensor/MAX17048Sensor.h"
|
||||
#include <utility>
|
||||
extern std::pair<uint8_t, TwoWire *> nodeTelemetrySensorsMap[_meshtastic_TelemetrySensorType_MAX + 1];
|
||||
@ -87,7 +87,7 @@ MAX17048Sensor max17048Sensor;
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if HAS_RAKPROT && !defined(ARCH_PORTDUINO)
|
||||
#if HAS_RAKPROT
|
||||
RAK9154Sensor rak9154Sensor;
|
||||
#endif
|
||||
|
||||
@ -198,7 +198,7 @@ class AnalogBatteryLevel : public HasBatteryLevel
|
||||
*/
|
||||
virtual int getBatteryPercent() override
|
||||
{
|
||||
#if defined(HAS_RAKPROT) && !defined(ARCH_PORTDUINO) && !defined(HAS_PMU)
|
||||
#if defined(HAS_RAKPROT) && !defined(HAS_PMU)
|
||||
if (hasRAK()) {
|
||||
return rak9154Sensor.getBusBatteryPercent();
|
||||
}
|
||||
@ -243,14 +243,13 @@ class AnalogBatteryLevel : public HasBatteryLevel
|
||||
virtual uint16_t getBattVoltage() override
|
||||
{
|
||||
|
||||
#if defined(HAS_RAKPROT) && !defined(ARCH_PORTDUINO) && !defined(HAS_PMU)
|
||||
#if defined(HAS_RAKPROT) && !defined(HAS_PMU)
|
||||
if (hasRAK()) {
|
||||
return getRAKVoltage();
|
||||
}
|
||||
#endif
|
||||
|
||||
#if HAS_TELEMETRY && !defined(ARCH_PORTDUINO) && !defined(ARCH_STM32WL) && !defined(HAS_PMU) && \
|
||||
!MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
|
||||
#if HAS_TELEMETRY && !defined(ARCH_STM32WL) && !defined(HAS_PMU) && !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
|
||||
if (hasINA()) {
|
||||
return getINAVoltage();
|
||||
}
|
||||
@ -406,7 +405,7 @@ class AnalogBatteryLevel : public HasBatteryLevel
|
||||
/// we can't be smart enough to say 'full'?
|
||||
virtual bool isCharging() override
|
||||
{
|
||||
#if defined(HAS_RAKPROT) && !defined(ARCH_PORTDUINO) && !defined(HAS_PMU)
|
||||
#if defined(HAS_RAKPROT) && !defined(HAS_PMU)
|
||||
if (hasRAK()) {
|
||||
return (rak9154Sensor.isCharging()) ? OptTrue : OptFalse;
|
||||
}
|
||||
@ -414,7 +413,7 @@ class AnalogBatteryLevel : public HasBatteryLevel
|
||||
#ifdef EXT_CHRG_DETECT
|
||||
return digitalRead(EXT_CHRG_DETECT) == ext_chrg_detect_value;
|
||||
#else
|
||||
#if HAS_TELEMETRY && !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR && !defined(ARCH_PORTDUINO) && !defined(ARCH_STM32WL) && \
|
||||
#if HAS_TELEMETRY && !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR && !defined(ARCH_STM32WL) && \
|
||||
!defined(DISABLE_INA_CHARGING_DETECTION)
|
||||
if (hasINA()) {
|
||||
// get current flow from INA sensor - negative value means power flowing into the battery
|
||||
@ -459,7 +458,7 @@ class AnalogBatteryLevel : public HasBatteryLevel
|
||||
}
|
||||
#endif
|
||||
|
||||
#if HAS_TELEMETRY && !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR && !defined(ARCH_PORTDUINO) && !defined(ARCH_STM32WL)
|
||||
#if HAS_TELEMETRY && !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR && !defined(ARCH_STM32WL)
|
||||
uint16_t getINAVoltage()
|
||||
{
|
||||
if (nodeTelemetrySensorsMap[meshtastic_TelemetrySensorType_INA219].first == config.power.device_battery_ina_address) {
|
||||
@ -1113,7 +1112,7 @@ bool Power::axpChipInit()
|
||||
#endif
|
||||
}
|
||||
|
||||
#if !MESHTASTIC_EXCLUDE_I2C && !defined(ARCH_PORTDUINO) && !defined(ARCH_STM32WL)
|
||||
#if !MESHTASTIC_EXCLUDE_I2C && !defined(ARCH_STM32WL)
|
||||
|
||||
/**
|
||||
* Wrapper class for an I2C MAX17048 Lipo battery sensor.
|
||||
|
13
src/main.cpp
13
src/main.cpp
@ -105,7 +105,7 @@ NRF52Bluetooth *nrf52Bluetooth = nullptr;
|
||||
#include "AmbientLightingThread.h"
|
||||
#include "PowerFSMThread.h"
|
||||
|
||||
#if !defined(ARCH_PORTDUINO) && !defined(ARCH_STM32WL) && !MESHTASTIC_EXCLUDE_I2C
|
||||
#if !defined(ARCH_STM32WL) && !MESHTASTIC_EXCLUDE_I2C
|
||||
#include "motion/AccelerometerThread.h"
|
||||
AccelerometerThread *accelerometerThread = nullptr;
|
||||
#endif
|
||||
@ -168,11 +168,6 @@ bool pauseBluetoothLogging = false;
|
||||
|
||||
bool pmu_found;
|
||||
|
||||
#if !MESHTASTIC_EXCLUDE_I2C
|
||||
// Array map of sensor types with i2c address and wire as we'll find in the i2c scan
|
||||
std::pair<uint8_t, TwoWire *> nodeTelemetrySensorsMap[_meshtastic_TelemetrySensorType_MAX + 1] = {};
|
||||
#endif
|
||||
|
||||
Router *router = NULL; // Users of router don't care what sort of subclass implements that API
|
||||
|
||||
const char *firmware_version = optstr(APP_VERSION_SHORT);
|
||||
@ -573,7 +568,7 @@ void setup()
|
||||
}
|
||||
#endif
|
||||
|
||||
#if !defined(ARCH_PORTDUINO) && !defined(ARCH_STM32WL)
|
||||
#if !defined(ARCH_STM32WL)
|
||||
auto acc_info = i2cScanner->firstAccelerometer();
|
||||
accelerometer_found = acc_info.type != ScanI2C::DeviceType::NONE ? acc_info.address : accelerometer_found;
|
||||
LOG_DEBUG("acc_info = %i", acc_info.type);
|
||||
@ -683,7 +678,7 @@ void setup()
|
||||
#endif
|
||||
|
||||
#if !MESHTASTIC_EXCLUDE_I2C
|
||||
#if !defined(ARCH_PORTDUINO) && !defined(ARCH_STM32WL)
|
||||
#if !defined(ARCH_STM32WL)
|
||||
if (acc_info.type != ScanI2C::DeviceType::NONE) {
|
||||
accelerometerThread = new AccelerometerThread(acc_info.type);
|
||||
}
|
||||
@ -691,7 +686,7 @@ void setup()
|
||||
|
||||
#if defined(HAS_NEOPIXEL) || defined(UNPHONE) || defined(RGBLED_RED)
|
||||
ambientLightingThread = new AmbientLightingThread(ScanI2C::DeviceType::NONE);
|
||||
#elif !defined(ARCH_PORTDUINO) && !defined(ARCH_STM32WL)
|
||||
#elif !defined(ARCH_STM32WL)
|
||||
if (rgb_found.type != ScanI2C::DeviceType::NONE) {
|
||||
ambientLightingThread = new AmbientLightingThread(rgb_found.type);
|
||||
}
|
||||
|
@ -20,6 +20,7 @@ extern NRF52Bluetooth *nrf52Bluetooth;
|
||||
#endif
|
||||
#if !MESHTASTIC_EXCLUDE_I2C
|
||||
#include "detect/ScanI2CTwoWire.h"
|
||||
std::pair<uint8_t, TwoWire *> nodeTelemetrySensorsMap[_meshtastic_TelemetrySensorType_MAX + 1] = {};
|
||||
#endif
|
||||
|
||||
#if ARCH_PORTDUINO
|
||||
@ -52,7 +53,7 @@ extern AudioThread *audioThread;
|
||||
// Global Screen singleton.
|
||||
extern graphics::Screen *screen;
|
||||
|
||||
#if !defined(ARCH_PORTDUINO) && !defined(ARCH_STM32WL) && !MESHTASTIC_EXCLUDE_I2C
|
||||
#if !defined(ARCH_STM32WL) && !MESHTASTIC_EXCLUDE_I2C
|
||||
#include "motion/AccelerometerThread.h"
|
||||
extern AccelerometerThread *accelerometerThread;
|
||||
#endif
|
||||
|
@ -43,7 +43,7 @@
|
||||
BMP085Sensor bmp085Sensor;
|
||||
BMP280Sensor bmp280Sensor;
|
||||
BME280Sensor bme280Sensor;
|
||||
BME680Sensor bme680Sensor;
|
||||
// BME680Sensor bme680Sensor;
|
||||
MCP9808Sensor mcp9808Sensor;
|
||||
SHTC3Sensor shtc3Sensor;
|
||||
LPS22HBSensor lps22hbSensor;
|
||||
@ -123,8 +123,8 @@ int32_t EnvironmentTelemetryModule::runOnce()
|
||||
result = bme280Sensor.runOnce();
|
||||
if (bmp3xxSensor.hasSensor())
|
||||
result = bmp3xxSensor.runOnce();
|
||||
if (bme680Sensor.hasSensor())
|
||||
result = bme680Sensor.runOnce();
|
||||
// if (bme680Sensor.hasSensor())
|
||||
// result = bme680Sensor.runOnce();
|
||||
if (mcp9808Sensor.hasSensor())
|
||||
result = mcp9808Sensor.runOnce();
|
||||
if (shtc3Sensor.hasSensor())
|
||||
@ -167,7 +167,7 @@ int32_t EnvironmentTelemetryModule::runOnce()
|
||||
if (!moduleConfig.telemetry.environment_measurement_enabled) {
|
||||
return disable();
|
||||
} else {
|
||||
#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR_EXTERNAL
|
||||
#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR_EXTERNAL && !defined(ARCH_PORTDUINO)
|
||||
if (bme680Sensor.hasSensor())
|
||||
result = bme680Sensor.runTrigger();
|
||||
#endif
|
||||
@ -400,10 +400,12 @@ bool EnvironmentTelemetryModule::getEnvironmentTelemetry(meshtastic_Telemetry *m
|
||||
valid = valid && bmp3xxSensor.getMetrics(m);
|
||||
hasSensor = true;
|
||||
}
|
||||
#if !defined(ARCH_PORTDUINO)
|
||||
if (bme680Sensor.hasSensor()) {
|
||||
valid = valid && bme680Sensor.getMetrics(m);
|
||||
hasSensor = true;
|
||||
}
|
||||
#endif
|
||||
if (mcp9808Sensor.hasSensor()) {
|
||||
valid = valid && mcp9808Sensor.getMetrics(m);
|
||||
hasSensor = true;
|
||||
@ -604,11 +606,13 @@ AdminMessageHandleResult EnvironmentTelemetryModule::handleAdminMessageForModule
|
||||
if (result != AdminMessageHandleResult::NOT_HANDLED)
|
||||
return result;
|
||||
}
|
||||
#if !defined(ARCH_PORTDUINO)
|
||||
if (bme680Sensor.hasSensor()) {
|
||||
result = bme680Sensor.handleAdminMessage(mp, request, response);
|
||||
if (result != AdminMessageHandleResult::NOT_HANDLED)
|
||||
return result;
|
||||
}
|
||||
#endif
|
||||
if (mcp9808Sensor.hasSensor()) {
|
||||
result = mcp9808Sensor.handleAdminMessage(mp, request, response);
|
||||
if (result != AdminMessageHandleResult::NOT_HANDLED)
|
||||
|
@ -1,6 +1,6 @@
|
||||
#include "configuration.h"
|
||||
|
||||
#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
|
||||
#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR && !ARCH_PORTDUINO
|
||||
|
||||
#include "../mesh/generated/meshtastic/telemetry.pb.h"
|
||||
#include "BME680Sensor.h"
|
||||
|
@ -1,6 +1,6 @@
|
||||
#include "configuration.h"
|
||||
|
||||
#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
|
||||
#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR && !ARCH_PORTDUINO
|
||||
|
||||
#include "../mesh/generated/meshtastic/telemetry.pb.h"
|
||||
#include "TelemetrySensor.h"
|
||||
|
@ -5,7 +5,7 @@
|
||||
|
||||
#include "configuration.h"
|
||||
|
||||
#if !MESHTASTIC_EXCLUDE_I2C && !defined(ARCH_PORTDUINO) && !defined(ARCH_STM32WL)
|
||||
#if !MESHTASTIC_EXCLUDE_I2C && !defined(ARCH_STM32WL)
|
||||
|
||||
// Samples to store in a buffer to determine if the battery is charging or discharging
|
||||
#define MAX17048_CHARGING_SAMPLES 3
|
||||
|
@ -4,11 +4,12 @@
|
||||
|
||||
#pragma once
|
||||
#include "../mesh/generated/meshtastic/telemetry.pb.h"
|
||||
#include "Arduino.h"
|
||||
#include "MeshModule.h"
|
||||
#include "NodeDB.h"
|
||||
#include <utility>
|
||||
|
||||
class TwoWire;
|
||||
// class TwoWire;
|
||||
|
||||
#define DEFAULT_SENSOR_MINIMUM_WAIT_TIME_BETWEEN_READS 1000
|
||||
extern std::pair<uint8_t, TwoWire *> nodeTelemetrySensorsMap[_meshtastic_TelemetrySensorType_MAX + 1];
|
||||
|
@ -4,7 +4,7 @@
|
||||
|
||||
#include "configuration.h"
|
||||
|
||||
#if !defined(ARCH_PORTDUINO) && !defined(ARCH_STM32WL) && !MESHTASTIC_EXCLUDE_I2C
|
||||
#if !defined(ARCH_STM32WL) && !MESHTASTIC_EXCLUDE_I2C
|
||||
|
||||
#include "../concurrency/OSThread.h"
|
||||
#ifdef HAS_BMA423
|
||||
|
@ -1,6 +1,6 @@
|
||||
#include "BMX160Sensor.h"
|
||||
|
||||
#if !defined(ARCH_PORTDUINO) && !defined(ARCH_STM32WL) && !MESHTASTIC_EXCLUDE_I2C
|
||||
#if !defined(ARCH_STM32WL) && !MESHTASTIC_EXCLUDE_I2C
|
||||
|
||||
BMX160Sensor::BMX160Sensor(ScanI2C::FoundDevice foundDevice) : MotionSensor::MotionSensor(foundDevice) {}
|
||||
|
||||
|
@ -5,7 +5,7 @@
|
||||
|
||||
#include "MotionSensor.h"
|
||||
|
||||
#if !defined(ARCH_PORTDUINO) && !defined(ARCH_STM32WL) && !MESHTASTIC_EXCLUDE_I2C
|
||||
#if !defined(ARCH_STM32WL) && !MESHTASTIC_EXCLUDE_I2C
|
||||
|
||||
#ifdef RAK_4631
|
||||
|
||||
|
@ -1,6 +1,6 @@
|
||||
#include "ICM20948Sensor.h"
|
||||
|
||||
#if !defined(ARCH_PORTDUINO) && !defined(ARCH_STM32WL) && !MESHTASTIC_EXCLUDE_I2C
|
||||
#if !defined(ARCH_STM32WL) && !MESHTASTIC_EXCLUDE_I2C
|
||||
|
||||
// Flag when an interrupt has been detected
|
||||
volatile static bool ICM20948_IRQ = false;
|
||||
|
@ -4,7 +4,7 @@
|
||||
|
||||
#include "MotionSensor.h"
|
||||
|
||||
#if !defined(ARCH_PORTDUINO) && !defined(ARCH_STM32WL) && !MESHTASTIC_EXCLUDE_I2C
|
||||
#if !defined(ARCH_STM32WL) && !MESHTASTIC_EXCLUDE_I2C
|
||||
|
||||
#include <ICM_20948.h>
|
||||
|
||||
|
@ -1,7 +1,7 @@
|
||||
#include "LIS3DHSensor.h"
|
||||
#include "NodeDB.h"
|
||||
|
||||
#if !defined(ARCH_PORTDUINO) && !defined(ARCH_STM32WL) && !MESHTASTIC_EXCLUDE_I2C
|
||||
#if !defined(ARCH_STM32WL) && !MESHTASTIC_EXCLUDE_I2C
|
||||
|
||||
LIS3DHSensor::LIS3DHSensor(ScanI2C::FoundDevice foundDevice) : MotionSensor::MotionSensor(foundDevice) {}
|
||||
|
||||
|
@ -4,7 +4,7 @@
|
||||
|
||||
#include "MotionSensor.h"
|
||||
|
||||
#if !defined(ARCH_PORTDUINO) && !defined(ARCH_STM32WL) && !MESHTASTIC_EXCLUDE_I2C
|
||||
#if !defined(ARCH_STM32WL) && !MESHTASTIC_EXCLUDE_I2C
|
||||
|
||||
#include <Adafruit_LIS3DH.h>
|
||||
|
||||
|
@ -1,7 +1,7 @@
|
||||
#include "LSM6DS3Sensor.h"
|
||||
#include "NodeDB.h"
|
||||
|
||||
#if !defined(ARCH_PORTDUINO) && !defined(ARCH_STM32WL) && !MESHTASTIC_EXCLUDE_I2C
|
||||
#if !defined(ARCH_STM32WL) && !MESHTASTIC_EXCLUDE_I2C
|
||||
|
||||
LSM6DS3Sensor::LSM6DS3Sensor(ScanI2C::FoundDevice foundDevice) : MotionSensor::MotionSensor(foundDevice) {}
|
||||
|
||||
|
@ -4,7 +4,7 @@
|
||||
|
||||
#include "MotionSensor.h"
|
||||
|
||||
#if !defined(ARCH_PORTDUINO) && !defined(ARCH_STM32WL) && !MESHTASTIC_EXCLUDE_I2C
|
||||
#if !defined(ARCH_STM32WL) && !MESHTASTIC_EXCLUDE_I2C
|
||||
|
||||
#ifndef LSM6DS3_WAKE_THRESH
|
||||
#define LSM6DS3_WAKE_THRESH 20
|
||||
|
@ -1,6 +1,6 @@
|
||||
#include "MPU6050Sensor.h"
|
||||
|
||||
#if !defined(ARCH_PORTDUINO) && !defined(ARCH_STM32WL) && !MESHTASTIC_EXCLUDE_I2C
|
||||
#if !defined(ARCH_STM32WL) && !MESHTASTIC_EXCLUDE_I2C
|
||||
|
||||
MPU6050Sensor::MPU6050Sensor(ScanI2C::FoundDevice foundDevice) : MotionSensor::MotionSensor(foundDevice) {}
|
||||
|
||||
|
@ -4,7 +4,7 @@
|
||||
|
||||
#include "MotionSensor.h"
|
||||
|
||||
#if !defined(ARCH_PORTDUINO) && !defined(ARCH_STM32WL) && !MESHTASTIC_EXCLUDE_I2C
|
||||
#if !defined(ARCH_STM32WL) && !MESHTASTIC_EXCLUDE_I2C
|
||||
|
||||
#include <Adafruit_MPU6050.h>
|
||||
|
||||
|
@ -7,7 +7,7 @@
|
||||
|
||||
#include "../configuration.h"
|
||||
|
||||
#if !defined(ARCH_PORTDUINO) && !defined(ARCH_STM32WL) && !MESHTASTIC_EXCLUDE_I2C
|
||||
#if !defined(ARCH_STM32WL) && !MESHTASTIC_EXCLUDE_I2C
|
||||
|
||||
#include "../PowerFSM.h"
|
||||
#include "../detect/ScanI2C.h"
|
||||
|
@ -20,3 +20,6 @@
|
||||
#ifndef HAS_TELEMETRY
|
||||
#define HAS_TELEMETRY 1
|
||||
#endif
|
||||
#ifndef HAS_SENSOR
|
||||
#define HAS_SENSOR 1
|
||||
#endif
|
@ -40,7 +40,7 @@ extern RTC_NOINIT_ATTR uint64_t RTC_reg_b;
|
||||
#include "soc/sens_reg.h" // needed for adc pin reset
|
||||
#endif
|
||||
|
||||
#if HAS_TELEMETRY && !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR && !defined(ARCH_PORTDUINO)
|
||||
#if HAS_TELEMETRY && !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
|
||||
#include "modules/Telemetry/Sensor/INA219Sensor.h"
|
||||
#include "modules/Telemetry/Sensor/INA226Sensor.h"
|
||||
#include "modules/Telemetry/Sensor/INA260Sensor.h"
|
||||
@ -51,12 +51,12 @@ extern INA260Sensor ina260Sensor;
|
||||
extern INA3221Sensor ina3221Sensor;
|
||||
#endif
|
||||
|
||||
#if HAS_TELEMETRY && !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR && !defined(ARCH_PORTDUINO) && !defined(ARCH_STM32WL)
|
||||
#if HAS_TELEMETRY && !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR && !defined(ARCH_STM32WL)
|
||||
#include "modules/Telemetry/Sensor/MAX17048Sensor.h"
|
||||
extern MAX17048Sensor max17048Sensor;
|
||||
#endif
|
||||
|
||||
#if HAS_RAKPROT && !defined(ARCH_PORTDUINO)
|
||||
#if HAS_RAKPROT
|
||||
#include "../variants/rak2560/RAK9154Sensor.h"
|
||||
extern RAK9154Sensor rak9154Sensor;
|
||||
#endif
|
||||
|
Loading…
Reference in New Issue
Block a user