mirror of
https://github.com/meshtastic/firmware.git
synced 2025-08-01 03:15:42 +00:00
WIP
This commit is contained in:
parent
7a7ef5f0c9
commit
fd5ff679f3
@ -41,7 +41,7 @@ template <typename T, std::size_t N> std::size_t array_count(const T (&)[N])
|
||||
|
||||
#if defined(NRF52840_XXAA) || defined(NRF52833_XXAA) || defined(ARCH_ESP32) || defined(ARCH_PORTDUINO)
|
||||
#if defined(SENSECAP_INDICATOR)
|
||||
FakeUART *GPS::_serial_gps = nullptr;
|
||||
FakeUART *GPS::_serial_gps = FakeSerial;
|
||||
#elif defined(RAK2560)
|
||||
HardwareSerial *GPS::_serial_gps = &Serial2;
|
||||
#else
|
||||
|
@ -12,7 +12,7 @@
|
||||
#include "modules/PositionModule.h"
|
||||
|
||||
#ifdef SENSECAP_INDICATOR
|
||||
#include "FakeUART.h"
|
||||
#include "mesh/comms/FakeUART.h"
|
||||
#endif
|
||||
|
||||
// Allow defining the polarity of the ENABLE output. default is active high
|
||||
|
17
src/main.cpp
17
src/main.cpp
@ -24,6 +24,7 @@
|
||||
|
||||
#ifdef SENSECAP_INDICATOR // on the indicator run the additional serial port for the RP2040
|
||||
#include "IndicatorSerial.h"
|
||||
#include "mesh/comms/FakeI2C.h"
|
||||
#endif
|
||||
|
||||
#if !MESHTASTIC_EXCLUDE_I2C
|
||||
@ -461,7 +462,11 @@ void setup()
|
||||
fsInit();
|
||||
|
||||
#if !MESHTASTIC_EXCLUDE_I2C
|
||||
#if defined(I2C_SDA1) && defined(ARCH_RP2040)
|
||||
// The Sensecap Indicator hast I2C on the secondary MCU. Tunnel this as wire1
|
||||
#if defined(SENSECAP_INDICATOR)
|
||||
FakeI2C Wire1 = *FakeWire;
|
||||
Wire1.begin();
|
||||
#elif defined(I2C_SDA1) && defined(ARCH_RP2040)
|
||||
Wire1.setSDA(I2C_SDA1);
|
||||
Wire1.setSCL(I2C_SCL1);
|
||||
Wire1.begin();
|
||||
@ -519,7 +524,9 @@ void setup()
|
||||
LOG_INFO("Scan for i2c devices");
|
||||
#endif
|
||||
|
||||
#if defined(I2C_SDA1) && defined(ARCH_RP2040)
|
||||
#if defined(SENSECAP_INDICATOR)
|
||||
i2cScanner->scanPort(ScanI2C::I2CPort::WIRE1);
|
||||
#elif defined(I2C_SDA1) && defined(ARCH_RP2040)
|
||||
Wire1.setSDA(I2C_SDA1);
|
||||
Wire1.setSCL(I2C_SCL1);
|
||||
Wire1.begin();
|
||||
@ -754,7 +761,11 @@ void setup()
|
||||
|
||||
// If we have an indicator, start process to service secondary port
|
||||
#ifdef SENSECAP_INDICATOR
|
||||
sensecapIndicator.begin(Serial2);
|
||||
#if SENSOR_PORT_NUM == 2
|
||||
sensecapIndicator = new SensecapIndicator(Serial2);
|
||||
#elif SENSOR_PORT_NUM == 1
|
||||
sensecapIndicator = new SensecapIndicator(Serial1);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// only play start melody when role is not tracker or sensor
|
||||
|
@ -1,24 +1,20 @@
|
||||
#ifdef SENSECAP_INDICATOR
|
||||
|
||||
#include "IndicatorSerial.h"
|
||||
#include "../modules/Telemetry/Sensor/IndicatorSensor.h"
|
||||
#include "FakeUART.h"
|
||||
#include "mesh/comms/FakeUART.h"
|
||||
#include "mesh/comms/FakeI2C.h"
|
||||
#include <HardwareSerial.h>
|
||||
#include <pb_decode.h>
|
||||
#include <pb_encode.h>
|
||||
|
||||
extern IndicatorSensor indicatorSensor;
|
||||
SensecapIndicator *sensecapIndicator;
|
||||
|
||||
SensecapIndicator sensecapIndicator;
|
||||
|
||||
SensecapIndicator::SensecapIndicator() : OSThread("SensecapIndicator") {}
|
||||
|
||||
void SensecapIndicator::begin(HardwareSerial serial)
|
||||
{
|
||||
SensecapIndicator::SensecapIndicator(HardwareSerial &serial) : OSThread("SensecapIndicator") {
|
||||
if (!running) {
|
||||
_serial = serial;
|
||||
_serial.setRxBufferSize(PB_BUFSIZE);
|
||||
_serial.begin(115200);
|
||||
_serial = &serial;
|
||||
_serial->setRxBufferSize(PB_BUFSIZE);
|
||||
_serial->setPins(SENSOR_RP2040_RXD, SENSOR_RP2040_TXD);
|
||||
_serial->begin(SENSOR_BAUD_RATE);
|
||||
running = true;
|
||||
LOG_DEBUG("Start communication thread");
|
||||
}
|
||||
@ -66,8 +62,8 @@ bool SensecapIndicator::send_uplink(meshtastic_InterdeviceMessage message)
|
||||
size_t SensecapIndicator::serial_check(char *buf, size_t space_left)
|
||||
{
|
||||
size_t bytes_read = 0;
|
||||
while (_serial.available()) {
|
||||
char c = _serial.read();
|
||||
while (_serial->available()) {
|
||||
char c = _serial->read();
|
||||
*buf++ = c;
|
||||
if (++bytes_read >= space_left) {
|
||||
LOG_DEBUG("Serial overflow: %d > %d", bytes_read, space_left);
|
||||
@ -124,8 +120,13 @@ bool SensecapIndicator::handle_packet(size_t payload_len)
|
||||
return false;
|
||||
}
|
||||
switch (message.which_data) {
|
||||
case meshtastic_InterdeviceMessage_sensor_tag:
|
||||
indicatorSensor.stuff_buffer(message.data.sensor);
|
||||
case meshtastic_InterdeviceMessage_i2c_response_tag:
|
||||
if (message.data.i2c_response.status != meshtastic_I2CResponse_Status_OK) {
|
||||
LOG_DEBUG("I2C response error: %d", message.data.i2c_response.status);
|
||||
return false;
|
||||
}
|
||||
// send I2C response to FakeI2C
|
||||
FakeWire->ingest(message.data.i2c_response);
|
||||
return true;
|
||||
break;
|
||||
case meshtastic_InterdeviceMessage_nmea_tag:
|
||||
@ -142,7 +143,7 @@ bool SensecapIndicator::handle_packet(size_t payload_len)
|
||||
|
||||
bool SensecapIndicator::send(const char *buf, size_t len)
|
||||
{
|
||||
size_t wrote = _serial.write(buf, len);
|
||||
size_t wrote = _serial->write(buf, len);
|
||||
if (wrote == len)
|
||||
return true;
|
||||
return false;
|
||||
|
@ -25,8 +25,7 @@
|
||||
class SensecapIndicator : public concurrency::OSThread
|
||||
{
|
||||
public:
|
||||
SensecapIndicator();
|
||||
void begin(HardwareSerial serial);
|
||||
SensecapIndicator(HardwareSerial& serial);
|
||||
int32_t runOnce() override;
|
||||
bool send_uplink(meshtastic_InterdeviceMessage message);
|
||||
|
||||
@ -34,7 +33,7 @@ class SensecapIndicator : public concurrency::OSThread
|
||||
pb_byte_t pb_tx_buf[PB_BUFSIZE];
|
||||
pb_byte_t pb_rx_buf[PB_BUFSIZE];
|
||||
size_t pb_rx_size = 0; // Number of bytes currently in the buffer
|
||||
HardwareSerial _serial = Serial2;
|
||||
HardwareSerial* _serial = &Serial2;
|
||||
bool running = false;
|
||||
size_t serial_check(char *buf, size_t space_left);
|
||||
void check_packet();
|
||||
@ -42,7 +41,7 @@ class SensecapIndicator : public concurrency::OSThread
|
||||
bool send(const char *buf, size_t len);
|
||||
};
|
||||
|
||||
extern SensecapIndicator sensecapIndicator;
|
||||
extern SensecapIndicator *sensecapIndicator;
|
||||
|
||||
#endif // SENSECAP_INDICATOR
|
||||
#endif // INDICATORSERIAL_H
|
103
src/mesh/comms/FakeI2C.cpp
Normal file
103
src/mesh/comms/FakeI2C.cpp
Normal file
@ -0,0 +1,103 @@
|
||||
// File: /master/FakeI2C.cpp
|
||||
|
||||
#include "FakeI2C.h"
|
||||
|
||||
#ifdef SENSECAP_INDICATOR
|
||||
|
||||
FakeI2C *FakeWire;
|
||||
|
||||
void FakeI2C::begin() {}
|
||||
|
||||
void FakeI2C::beginTransmission(uint8_t address) {
|
||||
_currentAddress = address;
|
||||
// create a default interdevice message for I2C start
|
||||
meshtastic_InterdeviceMessage cmd = meshtastic_InterdeviceMessage_init_default;
|
||||
cmd.which_data = meshtastic_InterdeviceMessage_i2c_command_tag;
|
||||
cmd.data.i2c_command.op = meshtastic_I2CCommand_Operation_START;
|
||||
cmd.data.i2c_command.addr = _currentAddress;
|
||||
sensecapIndicator->send_uplink(cmd);
|
||||
}
|
||||
|
||||
void FakeI2C::endTransmission() {
|
||||
meshtastic_InterdeviceMessage cmd = meshtastic_InterdeviceMessage_init_default;
|
||||
cmd.which_data = meshtastic_InterdeviceMessage_i2c_command_tag;
|
||||
cmd.data.i2c_command.op = meshtastic_I2CCommand_Operation_STOP;
|
||||
sensecapIndicator->send_uplink(cmd);
|
||||
}
|
||||
|
||||
void FakeI2C::write(uint8_t val) {
|
||||
meshtastic_InterdeviceMessage cmd = meshtastic_InterdeviceMessage_init_default;
|
||||
cmd.which_data = meshtastic_InterdeviceMessage_i2c_command_tag;
|
||||
cmd.data.i2c_command.op = meshtastic_I2CCommand_Operation_WRITE;
|
||||
cmd.data.i2c_command.data = val;
|
||||
sensecapIndicator->send_uplink(cmd);
|
||||
}
|
||||
|
||||
uint8_t FakeI2C::requestFrom(uint8_t address, uint8_t quantity) {
|
||||
if (quantity != 1) return 0xFF;
|
||||
meshtastic_InterdeviceMessage cmd = meshtastic_InterdeviceMessage_init_default;
|
||||
cmd.which_data = meshtastic_InterdeviceMessage_i2c_command_tag;
|
||||
cmd.data.i2c_command.op = meshtastic_I2CCommand_Operation_READ;
|
||||
cmd.data.i2c_command.addr = address;
|
||||
cmd.data.i2c_command.ack = false;
|
||||
sensecapIndicator->send_uplink(cmd);
|
||||
// Wait for the response coming in asynchronously till there is a timeout
|
||||
|
||||
unsigned long start = millis();
|
||||
while (millis() - start < 100) {
|
||||
if (_pending) {
|
||||
_pending = false; // Clear the pending flag
|
||||
return 1; // Indicate that we have read one byte
|
||||
}
|
||||
delay(10); // Avoid busy waiting
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
int FakeI2C::read() {
|
||||
return _lastByte;
|
||||
}
|
||||
|
||||
uint8_t FakeI2C::readRegister(uint8_t reg) {
|
||||
beginTransmission(_currentAddress);
|
||||
write(reg);
|
||||
endTransmission();
|
||||
requestFrom(_currentAddress, 1);
|
||||
return read();
|
||||
}
|
||||
|
||||
void FakeI2C::writeRegister(uint8_t reg, uint8_t val) {
|
||||
beginTransmission(_currentAddress);
|
||||
write(reg);
|
||||
write(val);
|
||||
endTransmission();
|
||||
}
|
||||
|
||||
uint16_t FakeI2C::readRegister16(uint8_t reg) {
|
||||
beginTransmission(_currentAddress);
|
||||
write(reg);
|
||||
endTransmission();
|
||||
|
||||
uint16_t result = 0;
|
||||
for (int i = 0; i < 2; i++) {
|
||||
requestFrom(_currentAddress, 1);
|
||||
result |= ((uint16_t)read()) << (8 * (1 - i));
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
||||
void FakeI2C::writeRegister16(uint8_t reg, uint16_t val) {
|
||||
beginTransmission(_currentAddress);
|
||||
write(reg);
|
||||
write((uint8_t)(val >> 8));
|
||||
write((uint8_t)(val & 0xFF));
|
||||
endTransmission();
|
||||
}
|
||||
|
||||
void FakeI2C::ingest(meshtastic_I2CResponse data) {
|
||||
// Simulate receiving data as if it were from an I2C device
|
||||
_lastByte = data.data; // Store the last byte read
|
||||
_pending = true; // Indicate that we have pending data
|
||||
}
|
||||
|
||||
#endif // SENSECAP_INDICATOR
|
38
src/mesh/comms/FakeI2C.h
Normal file
38
src/mesh/comms/FakeI2C.h
Normal file
@ -0,0 +1,38 @@
|
||||
// File: /master/FakeI2C.h
|
||||
|
||||
#ifndef FAKEI2C_H
|
||||
#define FAKEI2C_H
|
||||
|
||||
#ifdef SENSECAP_INDICATOR
|
||||
|
||||
#include <Arduino.h>
|
||||
#include "../IndicatorSerial.h"
|
||||
#include "../generated/meshtastic/interdevice.pb.h"
|
||||
|
||||
class FakeI2C {
|
||||
public:
|
||||
void begin();
|
||||
void beginTransmission(uint8_t address);
|
||||
void endTransmission();
|
||||
void write(uint8_t val);
|
||||
uint8_t requestFrom(uint8_t address, uint8_t quantity);
|
||||
int read();
|
||||
|
||||
uint8_t readRegister(uint8_t reg);
|
||||
void writeRegister(uint8_t reg, uint8_t val);
|
||||
uint16_t readRegister16(uint8_t reg);
|
||||
void writeRegister16(uint8_t reg, uint16_t val);
|
||||
|
||||
void ingest(meshtastic_I2CResponse data);
|
||||
|
||||
private:
|
||||
uint8_t _currentAddress = 0;
|
||||
uint8_t _lastByte = 0;
|
||||
bool _pending = false; // Indicates if there is pending data to be read
|
||||
};
|
||||
|
||||
extern FakeI2C *FakeWire;
|
||||
|
||||
#endif // SENSECAP_INDICATOR
|
||||
|
||||
#endif // FAKEI2C_H
|
@ -2,6 +2,8 @@
|
||||
|
||||
#ifdef SENSECAP_INDICATOR
|
||||
|
||||
FakeUART *FakeSerial;
|
||||
|
||||
FakeUART::FakeUART() {}
|
||||
|
||||
void FakeUART::begin(unsigned long baud, uint32_t config, int8_t rxPin, int8_t txPin, bool invert, unsigned long timeout_ms,
|
||||
@ -9,6 +11,7 @@ void FakeUART::begin(unsigned long baud, uint32_t config, int8_t rxPin, int8_t t
|
||||
{
|
||||
baudrate = baud;
|
||||
FakeBuf.clear();
|
||||
LOG_DEBUG("FakeUART::begin(%lu)", baud);
|
||||
}
|
||||
|
||||
void FakeUART::end()
|
||||
@ -37,7 +40,7 @@ int FakeUART::read()
|
||||
return -1;
|
||||
}
|
||||
|
||||
void FakeUART::flush()
|
||||
void FakeUART::flush(bool wait)
|
||||
{
|
||||
FakeBuf.clear();
|
||||
}
|
||||
@ -74,7 +77,7 @@ size_t FakeUART::write(char *buffer, size_t size)
|
||||
size = sizeof(message.data.nmea); // Truncate if buffer is too large
|
||||
}
|
||||
memcpy(message.data.nmea, buffer, size);
|
||||
sensecapIndicator.send_uplink(message);
|
||||
sensecapIndicator->send_uplink(message);
|
||||
return size;
|
||||
}
|
||||
|
||||
@ -89,6 +92,4 @@ size_t FakeUART::stuff_buffer(const char *buffer, size_t size)
|
||||
return size;
|
||||
}
|
||||
|
||||
FakeUART *FakeSerial;
|
||||
|
||||
#endif
|
||||
#endif // SENSECAP_INDICATOR
|
@ -21,7 +21,7 @@ class FakeUART : public Stream
|
||||
int available();
|
||||
int peek();
|
||||
int read();
|
||||
void flush();
|
||||
void flush(bool wait = true);
|
||||
uint32_t baudRate();
|
||||
void updateBaudRate(unsigned long speed);
|
||||
size_t setRxBufferSize(size_t size);
|
@ -193,10 +193,6 @@ CGRadSensSensor cgRadSens;
|
||||
#include "Sensor/T1000xSensor.h"
|
||||
T1000xSensor t1000xSensor;
|
||||
#endif
|
||||
#ifdef SENSECAP_INDICATOR
|
||||
#include "Sensor/IndicatorSensor.h"
|
||||
IndicatorSensor indicatorSensor;
|
||||
#endif
|
||||
|
||||
#define FAILED_STATE_SENSOR_READ_MULTIPLIER 10
|
||||
#define DISPLAY_RECEIVEID_MEASUREMENTS_ON_SCREEN true
|
||||
@ -236,9 +232,6 @@ int32_t EnvironmentTelemetryModule::runOnce()
|
||||
|
||||
if (moduleConfig.telemetry.environment_measurement_enabled || ENVIRONMENTAL_TELEMETRY_MODULE_ENABLE) {
|
||||
LOG_INFO("Environment Telemetry: init");
|
||||
#ifdef SENSECAP_INDICATOR
|
||||
result = indicatorSensor.runOnce();
|
||||
#endif
|
||||
#ifdef T1000X_SENSOR_EN
|
||||
result = t1000xSensor.runOnce();
|
||||
#elif !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR_EXTERNAL
|
||||
@ -540,10 +533,6 @@ bool EnvironmentTelemetryModule::getEnvironmentTelemetry(meshtastic_Telemetry *m
|
||||
m->which_variant = meshtastic_Telemetry_environment_metrics_tag;
|
||||
m->variant.environment_metrics = meshtastic_EnvironmentMetrics_init_zero;
|
||||
|
||||
#ifdef SENSECAP_INDICATOR
|
||||
valid = valid && indicatorSensor.getMetrics(m);
|
||||
hasSensor = true;
|
||||
#endif
|
||||
#ifdef T1000X_SENSOR_EN // add by WayenWeng
|
||||
valid = valid && t1000xSensor.getMetrics(m);
|
||||
hasSensor = true;
|
||||
|
@ -1,91 +0,0 @@
|
||||
#include "configuration.h"
|
||||
|
||||
#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR && defined(SENSECAP_INDICATOR)
|
||||
|
||||
#include "IndicatorSensor.h"
|
||||
#include "IndicatorSerial.h"
|
||||
#include "TelemetrySensor.h"
|
||||
#include <Adafruit_Sensor.h>
|
||||
#include <driver/uart.h>
|
||||
|
||||
IndicatorSensor::IndicatorSensor() : TelemetrySensor(meshtastic_TelemetrySensorType_SENSOR_UNSET, "Indicator") {}
|
||||
|
||||
static int cmd_send(meshtastic_MessageType cmd, uint32_t value)
|
||||
{
|
||||
meshtastic_InterdeviceMessage message = meshtastic_InterdeviceMessage_init_zero;
|
||||
|
||||
message.data.sensor.type = cmd;
|
||||
message.data.sensor.data.uint32_value = value;
|
||||
return sensecapIndicator.send_uplink(message);
|
||||
}
|
||||
|
||||
int32_t IndicatorSensor::runOnce()
|
||||
{
|
||||
LOG_INFO("%s: init", sensorName);
|
||||
setup();
|
||||
return 2 * DEFAULT_SENSOR_MINIMUM_WAIT_TIME_BETWEEN_READS; // give it some time to start up
|
||||
}
|
||||
|
||||
void IndicatorSensor::setup()
|
||||
{
|
||||
cmd_send(meshtastic_MessageType_POWER_ON, 0);
|
||||
// measure and send only once every minute, for the phone API
|
||||
cmd_send(meshtastic_MessageType_COLLECT_INTERVAL, 60000);
|
||||
}
|
||||
|
||||
bool IndicatorSensor::getMetrics(meshtastic_Telemetry *measurement)
|
||||
{
|
||||
meshtastic_SensorData data = meshtastic_SensorData_init_zero;
|
||||
|
||||
if (ringBuf.pop(data)) {
|
||||
|
||||
switch (data.type) {
|
||||
case meshtastic_MessageType_SCD41_CO2: {
|
||||
|
||||
// LOG_DEBUG("CO2: %.1f", value);
|
||||
|
||||
break;
|
||||
}
|
||||
|
||||
case meshtastic_MessageType_AHT20_TEMP: {
|
||||
|
||||
// LOG_DEBUG("Temp: %.1f", value);
|
||||
|
||||
measurement->variant.environment_metrics.has_temperature = true;
|
||||
measurement->variant.environment_metrics.temperature = data.data.float_value;
|
||||
break;
|
||||
}
|
||||
|
||||
case meshtastic_MessageType_AHT20_HUMIDITY: {
|
||||
|
||||
// LOG_DEBUG("Humidity: %.1f", value);
|
||||
|
||||
measurement->variant.environment_metrics.has_relative_humidity = true;
|
||||
measurement->variant.environment_metrics.relative_humidity = data.data.float_value;
|
||||
break;
|
||||
}
|
||||
|
||||
case meshtastic_MessageType_TVOC_INDEX: {
|
||||
|
||||
// LOG_DEBUG("Tvoc: %.1f", value);
|
||||
|
||||
measurement->variant.environment_metrics.has_iaq = true;
|
||||
measurement->variant.environment_metrics.iaq = data.data.float_value;
|
||||
break;
|
||||
}
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
size_t IndicatorSensor::stuff_buffer(meshtastic_SensorData message)
|
||||
{
|
||||
|
||||
return ringBuf.push(message) ? 1 : 0;
|
||||
}
|
||||
|
||||
#endif
|
@ -1,25 +0,0 @@
|
||||
#include "configuration.h"
|
||||
|
||||
#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
|
||||
|
||||
#include "../mesh/generated/meshtastic/interdevice.pb.h"
|
||||
#include "../mesh/generated/meshtastic/telemetry.pb.h"
|
||||
#include "TelemetrySensor.h"
|
||||
#include <RingBuf.h>
|
||||
|
||||
class IndicatorSensor : public TelemetrySensor
|
||||
{
|
||||
protected:
|
||||
virtual void setup() override;
|
||||
|
||||
public:
|
||||
IndicatorSensor();
|
||||
virtual int32_t runOnce() override;
|
||||
virtual bool getMetrics(meshtastic_Telemetry *measurement) override;
|
||||
size_t stuff_buffer(meshtastic_SensorData message);
|
||||
|
||||
private:
|
||||
RingBuf<meshtastic_SensorData, 16> ringBuf;
|
||||
};
|
||||
|
||||
#endif
|
Loading…
Reference in New Issue
Block a user