Compare commits

...

8 Commits

Author SHA1 Message Date
Thomas Göttgens
c16ae9e1a0
Merge d544b41ab7 into a30f431b6a 2025-04-19 16:38:34 -04:00
renovate[bot]
a30f431b6a
Update Kongduino-Adafruit_nRFCrypto digest to 5f838d2 (#6634)
Some checks are pending
CI / build-esp32-c3 (push) Blocked by required conditions
CI / build-esp32-c6 (push) Blocked by required conditions
CI / build-nrf52 (push) Blocked by required conditions
CI / build-rpi2040 (push) Blocked by required conditions
CI / build-stm32 (push) Blocked by required conditions
CI / build-debian-src (push) Waiting to run
CI / package-pio-deps-native-tft (push) Waiting to run
CI / test-native (push) Waiting to run
CI / docker-deb-amd64 (push) Waiting to run
CI / docker-deb-amd64-tft (push) Waiting to run
CI / docker-alp-amd64 (push) Waiting to run
CI / docker-alp-amd64-tft (push) Waiting to run
CI / docker-deb-arm64 (push) Waiting to run
CI / docker-deb-armv7 (push) Waiting to run
CI / after-checks (push) Blocked by required conditions
CI / gather-artifacts (esp32) (push) Blocked by required conditions
CI / gather-artifacts (esp32c3) (push) Blocked by required conditions
CI / gather-artifacts (esp32c6) (push) Blocked by required conditions
CI / gather-artifacts (esp32s3) (push) Blocked by required conditions
CI / gather-artifacts (nrf52840) (push) Blocked by required conditions
CI / gather-artifacts (rp2040) (push) Blocked by required conditions
CI / gather-artifacts (stm32) (push) Blocked by required conditions
CI / release-artifacts (push) Blocked by required conditions
CI / release-firmware (esp32) (push) Blocked by required conditions
CI / release-firmware (esp32c3) (push) Blocked by required conditions
CI / release-firmware (esp32c6) (push) Blocked by required conditions
CI / release-firmware (esp32s3) (push) Blocked by required conditions
CI / release-firmware (nrf52840) (push) Blocked by required conditions
CI / release-firmware (rp2040) (push) Blocked by required conditions
CI / release-firmware (stm32) (push) Blocked by required conditions
Co-authored-by: renovate[bot] <29139614+renovate[bot]@users.noreply.github.com>
2025-04-19 18:49:05 +02:00
Austin
916afb5098
appdata.xml: Add date to all releases (#6632)
Some checks are pending
CI / build-esp32-c3 (push) Blocked by required conditions
CI / build-esp32-c6 (push) Blocked by required conditions
CI / build-nrf52 (push) Blocked by required conditions
CI / build-rpi2040 (push) Blocked by required conditions
CI / build-stm32 (push) Blocked by required conditions
CI / build-debian-src (push) Waiting to run
CI / package-pio-deps-native-tft (push) Waiting to run
CI / test-native (push) Waiting to run
CI / docker-deb-amd64 (push) Waiting to run
CI / docker-deb-amd64-tft (push) Waiting to run
CI / docker-alp-amd64 (push) Waiting to run
CI / docker-alp-amd64-tft (push) Waiting to run
CI / docker-deb-arm64 (push) Waiting to run
CI / docker-deb-armv7 (push) Waiting to run
CI / after-checks (push) Blocked by required conditions
CI / gather-artifacts (esp32) (push) Blocked by required conditions
CI / gather-artifacts (esp32c3) (push) Blocked by required conditions
CI / gather-artifacts (esp32c6) (push) Blocked by required conditions
CI / gather-artifacts (esp32s3) (push) Blocked by required conditions
CI / gather-artifacts (nrf52840) (push) Blocked by required conditions
CI / gather-artifacts (rp2040) (push) Blocked by required conditions
CI / gather-artifacts (stm32) (push) Blocked by required conditions
CI / release-artifacts (push) Blocked by required conditions
CI / release-firmware (esp32) (push) Blocked by required conditions
CI / release-firmware (esp32c3) (push) Blocked by required conditions
CI / release-firmware (esp32c6) (push) Blocked by required conditions
CI / release-firmware (esp32s3) (push) Blocked by required conditions
CI / release-firmware (nrf52840) (push) Blocked by required conditions
CI / release-firmware (rp2040) (push) Blocked by required conditions
CI / release-firmware (stm32) (push) Blocked by required conditions
2025-04-19 10:56:41 -04:00
Thomas Göttgens
d544b41ab7
Merge branch 'master' into indicator-comms 2025-03-31 11:09:44 +02:00
Thomas Göttgens
8c53ce82f2 don't build FakeUART on other platforms 2025-03-04 11:11:25 +01:00
Thomas Göttgens
7ee95f2a0c Merge branch 'indicator-comms' of github.com:meshtastic/firmware into indicator-comms 2025-03-04 10:39:35 +01:00
Thomas Göttgens
65b50babee get sensor and NMEA data from indicator. Will test tomorrow, don't merge yet. 2025-03-04 01:56:56 +01:00
Thomas Göttgens
3c30821337 get sensor and NMEA data from indicator. Will test tomorrow, don't merge yet. 2025-03-04 01:53:18 +01:00
14 changed files with 420 additions and 339 deletions

View File

@ -7,7 +7,7 @@ lib_deps =
${nrf52_base.lib_deps} ${nrf52_base.lib_deps}
${environmental_base.lib_deps} ${environmental_base.lib_deps}
# renovate: datasource=git-refs depName=Kongduino-Adafruit_nRFCrypto packageName=https://github.com/Kongduino/Adafruit_nRFCrypto gitBranch=master # renovate: datasource=git-refs depName=Kongduino-Adafruit_nRFCrypto packageName=https://github.com/Kongduino/Adafruit_nRFCrypto gitBranch=master
https://github.com/Kongduino/Adafruit_nRFCrypto/archive/e31a8825ea3300b163a0a3c1ddd5de34e10e1371.zip https://github.com/Kongduino/Adafruit_nRFCrypto/archive/5f838d2709461a2c981f642917aa50254a25c14c.zip
; Common NRF52 debugging settings follow. See the Meshtastic developer docs for how to connect SWD debugging probes to your board. ; Common NRF52 debugging settings follow. See the Meshtastic developer docs for how to connect SWD debugging probes to your board.

View File

@ -1,4 +1,4 @@
<?xml version="1.0" encoding="UTF-8"?> <?xml version='1.0' encoding='UTF-8'?>
<component type="desktop-application"> <component type="desktop-application">
<id>org.meshtastic.meshtasticd</id> <id>org.meshtastic.meshtasticd</id>
@ -87,13 +87,13 @@
</screenshots> </screenshots>
<releases> <releases>
<release version="2.6.6"> <release version="2.6.6" date="2025-04-15">
<url type="details">https://github.com/meshtastic/firmware/releases?q=tag%3Av2.6.6</url> <url type="details">https://github.com/meshtastic/firmware/releases?q=tag%3Av2.6.6</url>
</release> </release>
<release version="2.6.5" date="2025-04-09"> <release version="2.6.5" date="2025-03-30">
<url type="details">https://github.com/meshtastic/firmware/releases?q=tag%3Av2.6.5</url> <url type="details">https://github.com/meshtastic/firmware/releases?q=tag%3Av2.6.5</url>
</release> </release>
<release version="2.6.4" date="2025-03-29"> <release version="2.6.4" date="2025-03-28">
<url type="details">https://github.com/meshtastic/firmware/releases?q=tag%3Av2.6.4</url> <url type="details">https://github.com/meshtastic/firmware/releases?q=tag%3Av2.6.4</url>
</release> </release>
</releases> </releases>

94
src/gps/FakeUART.cpp Normal file
View File

@ -0,0 +1,94 @@
#include "FakeUART.h"
#ifdef SENSECAP_INDICATOR
FakeUART::FakeUART() {}
void FakeUART::begin(unsigned long baud, uint32_t config, int8_t rxPin, int8_t txPin, bool invert, unsigned long timeout_ms,
uint8_t rxfifo_full_thrhd)
{
baudrate = baud;
FakeBuf.clear();
}
void FakeUART::end()
{
FakeBuf.clear();
}
int FakeUART::available()
{
return FakeBuf.size();
}
int FakeUART::peek()
{
unsigned char ret;
if (FakeBuf.peek(ret))
return ret;
return -1;
}
int FakeUART::read()
{
unsigned char ret;
if (FakeBuf.pop(ret))
return ret;
return -1;
}
void FakeUART::flush()
{
FakeBuf.clear();
}
uint32_t FakeUART::baudRate()
{
return baudrate;
}
void FakeUART::updateBaudRate(unsigned long speed)
{
baudrate = speed;
}
size_t FakeUART::setRxBufferSize(size_t size)
{
return size;
}
size_t FakeUART::write(const char *buffer)
{
return write((char *)buffer, strlen(buffer));
}
size_t FakeUART::write(uint8_t *buffer, size_t size)
{
return write((char *)buffer, size);
}
size_t FakeUART::write(char *buffer, size_t size)
{
meshtastic_InterdeviceMessage message = meshtastic_InterdeviceMessage_init_zero;
if (size > sizeof(message.data.nmea)) {
size = sizeof(message.data.nmea); // Truncate if buffer is too large
}
memcpy(message.data.nmea, buffer, size);
sensecapIndicator.send_uplink(message);
return size;
}
size_t FakeUART::stuff_buffer(const char *buffer, size_t size)
{
// push buffer in a loop to FakeBuf
for (size_t i = 0; i < size; i++) {
if (!FakeBuf.push(buffer[i])) {
return i;
}
}
return size;
}
FakeUART *FakeSerial;
#endif

44
src/gps/FakeUART.h Normal file
View File

@ -0,0 +1,44 @@
#pragma once
#ifndef FAKEUART_H
#define FAKEUART_H
#ifdef SENSECAP_INDICATOR
#include "../IndicatorSerial.h"
#include <RingBuf.h>
#include <Stream.h>
#include <inttypes.h>
class FakeUART : public Stream
{
public:
FakeUART();
void begin(unsigned long baud, uint32_t config = 0x800001c, int8_t rxPin = -1, int8_t txPin = -1, bool invert = false,
unsigned long timeout_ms = 20000UL, uint8_t rxfifo_full_thrhd = 112);
void end();
int available();
int peek();
int read();
void flush();
uint32_t baudRate();
void updateBaudRate(unsigned long speed);
size_t setRxBufferSize(size_t size);
size_t write(const char *buffer);
size_t write(char *buffer, size_t size);
size_t write(uint8_t *buffer, size_t size);
size_t stuff_buffer(const char *buffer, size_t size);
virtual size_t write(uint8_t c) { return write(&c, 1); }
private:
unsigned long baudrate = 115200;
RingBuf<unsigned char, 2048> FakeBuf;
};
extern FakeUART *FakeSerial;
#endif // SENSECAP_INDICATOR
#endif // FAKEUART_H

View File

@ -40,7 +40,9 @@ 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(NRF52840_XXAA) || defined(NRF52833_XXAA) || defined(ARCH_ESP32) || defined(ARCH_PORTDUINO)
#if defined(RAK2560) #if defined(SENSECAP_INDICATOR)
FakeUART *GPS::_serial_gps = nullptr;
#elif defined(RAK2560)
HardwareSerial *GPS::_serial_gps = &Serial2; HardwareSerial *GPS::_serial_gps = &Serial2;
#else #else
HardwareSerial *GPS::_serial_gps = &Serial1; HardwareSerial *GPS::_serial_gps = &Serial1;

View File

@ -11,6 +11,10 @@
#include "input/UpDownInterruptImpl1.h" #include "input/UpDownInterruptImpl1.h"
#include "modules/PositionModule.h" #include "modules/PositionModule.h"
#ifdef SENSECAP_INDICATOR
#include "FakeUART.h"
#endif
// Allow defining the polarity of the ENABLE output. default is active high // Allow defining the polarity of the ENABLE output. default is active high
#ifndef GPS_EN_ACTIVE #ifndef GPS_EN_ACTIVE
#define GPS_EN_ACTIVE 1 #define GPS_EN_ACTIVE 1
@ -187,7 +191,9 @@ class GPS : private concurrency::OSThread
CallbackObserver<GPS, void *> notifyDeepSleepObserver = CallbackObserver<GPS, void *>(this, &GPS::prepareDeepSleep); CallbackObserver<GPS, void *> notifyDeepSleepObserver = CallbackObserver<GPS, void *>(this, &GPS::prepareDeepSleep);
/** If !NULL we will use this serial port to construct our GPS */ /** If !NULL we will use this serial port to construct our GPS */
#if defined(ARCH_RP2040) #if defined(SENSECAP_INDICATOR)
static FakeUART *_serial_gps;
#elif defined(ARCH_RP2040)
static SerialUART *_serial_gps; static SerialUART *_serial_gps;
#else #else
static HardwareSerial *_serial_gps; static HardwareSerial *_serial_gps;

View File

@ -22,6 +22,10 @@
#include "error.h" #include "error.h"
#include "power.h" #include "power.h"
#ifdef SENSECAP_INDICATOR // on the indicator run the additional serial port for the RP2040
#include "IndicatorSerial.h"
#endif
#if !MESHTASTIC_EXCLUDE_I2C #if !MESHTASTIC_EXCLUDE_I2C
#include "detect/ScanI2CTwoWire.h" #include "detect/ScanI2CTwoWire.h"
#include <Wire.h> #include <Wire.h>
@ -783,6 +787,11 @@ void setup()
buttonThread = new ButtonThread(); buttonThread = new ButtonThread();
#endif #endif
// If we have an indicator, start process to service secondary port
#ifdef SENSECAP_INDICATOR
sensecapIndicator.begin(Serial2);
#endif
// only play start melody when role is not tracker or sensor // only play start melody when role is not tracker or sensor
if (config.power.is_power_saving == true && if (config.power.is_power_saving == true &&
IS_ONE_OF(config.device.role, meshtastic_Config_DeviceConfig_Role_TRACKER, IS_ONE_OF(config.device.role, meshtastic_Config_DeviceConfig_Role_TRACKER,

View File

@ -0,0 +1,151 @@
#ifdef SENSECAP_INDICATOR
#include "IndicatorSerial.h"
#include "../modules/Telemetry/Sensor/IndicatorSensor.h"
#include "FakeUART.h"
#include <HardwareSerial.h>
#include <pb_decode.h>
#include <pb_encode.h>
extern IndicatorSensor indicatorSensor;
SensecapIndicator sensecapIndicator;
SensecapIndicator::SensecapIndicator() : OSThread("SensecapIndicator") {}
void SensecapIndicator::begin(HardwareSerial serial)
{
if (!running) {
_serial = serial;
_serial.setRxBufferSize(PB_BUFSIZE);
_serial.begin(115200);
running = true;
LOG_DEBUG("Start communication thread");
}
}
int32_t SensecapIndicator::runOnce()
{
if (running) {
size_t bytes_read = 0;
// See if there are any more bytes to add to our buffer.
size_t space_left = PB_BUFSIZE - pb_rx_size;
bytes_read = serial_check((char *)pb_rx_buf + pb_rx_size, space_left);
pb_rx_size += bytes_read;
check_packet();
return (10);
} else {
LOG_DEBUG("Not running");
return (1000);
}
}
bool SensecapIndicator::send_uplink(meshtastic_InterdeviceMessage message)
{
pb_tx_buf[0] = MT_MAGIC_0;
pb_tx_buf[1] = MT_MAGIC_1;
pb_ostream_t stream = pb_ostream_from_buffer(pb_tx_buf + MT_HEADER_SIZE, PB_BUFSIZE);
if (!pb_encode(&stream, meshtastic_InterdeviceMessage_fields, &message)) {
LOG_DEBUG("pb_encode failed");
return false;
}
// Store the payload length in the header
pb_tx_buf[2] = stream.bytes_written / 256;
pb_tx_buf[3] = stream.bytes_written % 256;
bool rv = send((const char *)pb_tx_buf, MT_HEADER_SIZE + stream.bytes_written);
return rv;
}
size_t SensecapIndicator::serial_check(char *buf, size_t space_left)
{
size_t bytes_read = 0;
while (_serial.available()) {
char c = _serial.read();
*buf++ = c;
if (++bytes_read >= space_left) {
LOG_DEBUG("Serial overflow: %d > %d", bytes_read, space_left);
break;
}
}
return bytes_read;
}
void SensecapIndicator::check_packet()
{
if (pb_rx_size < MT_HEADER_SIZE) {
// We don't even have a header yet
delay(NO_NEWS_PAUSE);
return;
}
if (pb_rx_buf[0] != MT_MAGIC_0 || pb_rx_buf[1] != MT_MAGIC_1) {
LOG_DEBUG("Got bad magic");
memset(pb_rx_buf, 0, PB_BUFSIZE);
pb_rx_size = 0;
return;
}
uint16_t payload_len = pb_rx_buf[2] << 8 | pb_rx_buf[3];
if (payload_len > PB_BUFSIZE) {
LOG_DEBUG("Got packet claiming to be ridiculous length");
return;
}
if ((size_t)(payload_len + 4) > pb_rx_size) {
delay(NO_NEWS_PAUSE);
return;
}
// We have a complete packet, handle it
handle_packet(payload_len);
}
bool SensecapIndicator::handle_packet(size_t payload_len)
{
meshtastic_InterdeviceMessage message = meshtastic_InterdeviceMessage_init_zero;
// Decode the protobuf and shift forward any remaining bytes in the buffer
// (which, if present, belong to the packet that we're going to process on the
// next loop)
pb_istream_t stream = pb_istream_from_buffer(pb_rx_buf + MT_HEADER_SIZE, payload_len);
bool status = pb_decode(&stream, meshtastic_InterdeviceMessage_fields, &message);
memmove(pb_rx_buf, pb_rx_buf + MT_HEADER_SIZE + payload_len, PB_BUFSIZE - MT_HEADER_SIZE - payload_len);
pb_rx_size -= MT_HEADER_SIZE + payload_len;
if (!status) {
LOG_DEBUG("Decoding failed");
return false;
}
switch (message.which_data) {
case meshtastic_InterdeviceMessage_sensor_tag:
indicatorSensor.stuff_buffer(message.data.sensor);
return true;
break;
case meshtastic_InterdeviceMessage_nmea_tag:
// send String to NMEA processing
FakeSerial->stuff_buffer(message.data.nmea, strlen(message.data.nmea));
return true;
break;
default:
// the other messages really only flow downstream
LOG_DEBUG("Got a message of unexpected type");
return false;
}
}
bool SensecapIndicator::send(const char *buf, size_t len)
{
size_t wrote = _serial.write(buf, len);
if (wrote == len)
return true;
return false;
}
#endif // SENSECAP_INDICATOR

View File

@ -0,0 +1,48 @@
#pragma once
#ifndef INDICATORSERIAL_H
#define INDICATORSERIAL_H
#ifdef SENSECAP_INDICATOR
#include "concurrency/OSThread.h"
#include "configuration.h"
#include "mesh/generated/meshtastic/interdevice.pb.h"
// Magic number at the start of all MT packets
#define MT_MAGIC_0 0x94
#define MT_MAGIC_1 0xc3
// The header is the magic number plus a 16-bit payload-length field
#define MT_HEADER_SIZE 4
// Wait this many msec if there's nothing new on the channel
#define NO_NEWS_PAUSE 25
#define PB_BUFSIZE meshtastic_InterdeviceMessage_size + MT_HEADER_SIZE
class SensecapIndicator : public concurrency::OSThread
{
public:
SensecapIndicator();
void begin(HardwareSerial serial);
int32_t runOnce() override;
bool send_uplink(meshtastic_InterdeviceMessage message);
private:
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;
bool running = false;
size_t serial_check(char *buf, size_t space_left);
void check_packet();
bool handle_packet(size_t payload_len);
bool send(const char *buf, size_t len);
};
extern SensecapIndicator sensecapIndicator;
#endif // SENSECAP_INDICATOR
#endif // INDICATORSERIAL_H

View File

@ -2,63 +2,21 @@
#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR && defined(SENSECAP_INDICATOR) #if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR && defined(SENSECAP_INDICATOR)
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "IndicatorSensor.h" #include "IndicatorSensor.h"
#include "IndicatorSerial.h"
#include "TelemetrySensor.h" #include "TelemetrySensor.h"
#include "serialization/cobs.h"
#include <Adafruit_Sensor.h> #include <Adafruit_Sensor.h>
#include <driver/uart.h> #include <driver/uart.h>
IndicatorSensor::IndicatorSensor() : TelemetrySensor(meshtastic_TelemetrySensorType_SENSOR_UNSET, "Indicator") {} IndicatorSensor::IndicatorSensor() : TelemetrySensor(meshtastic_TelemetrySensorType_SENSOR_UNSET, "Indicator") {}
#define SENSOR_BUF_SIZE (512) static int cmd_send(meshtastic_MessageType cmd, uint32_t value)
uint8_t buf[SENSOR_BUF_SIZE]; // recv
uint8_t data[SENSOR_BUF_SIZE]; // decode
#define ACK_PKT_PARA "ACK"
enum sensor_pkt_type {
PKT_TYPE_ACK = 0x00, // uin32_t
PKT_TYPE_CMD_COLLECT_INTERVAL = 0xA0, // uin32_t
PKT_TYPE_CMD_BEEP_ON = 0xA1, // uin32_t ms: on time
PKT_TYPE_CMD_BEEP_OFF = 0xA2,
PKT_TYPE_CMD_SHUTDOWN = 0xA3, // uin32_t
PKT_TYPE_CMD_POWER_ON = 0xA4,
PKT_TYPE_SENSOR_SCD41_TEMP = 0xB0, // float
PKT_TYPE_SENSOR_SCD41_HUMIDITY = 0xB1, // float
PKT_TYPE_SENSOR_SCD41_CO2 = 0xB2, // float
PKT_TYPE_SENSOR_AHT20_TEMP = 0xB3, // float
PKT_TYPE_SENSOR_AHT20_HUMIDITY = 0xB4, // float
PKT_TYPE_SENSOR_TVOC_INDEX = 0xB5, // float
};
static int cmd_send(uint8_t cmd, const char *p_data, uint8_t len)
{ {
uint8_t send_buf[32] = {0}; meshtastic_InterdeviceMessage message = meshtastic_InterdeviceMessage_init_zero;
uint8_t send_data[32] = {0};
if (len > 31) { message.data.sensor.type = cmd;
return -1; message.data.sensor.data.uint32_value = value;
} return sensecapIndicator.send_uplink(message);
uint8_t index = 1;
send_data[0] = cmd;
if (len > 0 && p_data != NULL) {
memcpy(&send_data[1], p_data, len);
index += len;
}
cobs_encode_result ret = cobs_encode(send_buf, sizeof(send_buf), send_data, index);
// LOG_DEBUG("cobs TX status:%d, len:%d, type 0x%x", ret.status, ret.out_len, cmd);
if (ret.status == COBS_ENCODE_OK) {
return uart_write_bytes(SENSOR_PORT_NUM, send_buf, ret.out_len + 1);
}
return -1;
} }
int32_t IndicatorSensor::runOnce() int32_t IndicatorSensor::runOnce()
@ -70,97 +28,64 @@ int32_t IndicatorSensor::runOnce()
void IndicatorSensor::setup() void IndicatorSensor::setup()
{ {
uart_config_t uart_config = { cmd_send(meshtastic_MessageType_POWER_ON, 0);
.baud_rate = SENSOR_BAUD_RATE,
.data_bits = UART_DATA_8_BITS,
.parity = UART_PARITY_DISABLE,
.stop_bits = UART_STOP_BITS_1,
.flow_ctrl = UART_HW_FLOWCTRL_DISABLE,
.source_clk = UART_SCLK_APB,
};
int intr_alloc_flags = 0;
char buffer[11];
uart_driver_install(SENSOR_PORT_NUM, SENSOR_BUF_SIZE * 2, 0, 0, NULL, intr_alloc_flags);
uart_param_config(SENSOR_PORT_NUM, &uart_config);
uart_set_pin(SENSOR_PORT_NUM, SENSOR_RP2040_TXD, SENSOR_RP2040_RXD, UART_PIN_NO_CHANGE, UART_PIN_NO_CHANGE);
cmd_send(PKT_TYPE_CMD_POWER_ON, NULL, 0);
// measure and send only once every minute, for the phone API // measure and send only once every minute, for the phone API
const char *interval = ultoa(60000, buffer, 10); cmd_send(meshtastic_MessageType_COLLECT_INTERVAL, 60000);
cmd_send(PKT_TYPE_CMD_COLLECT_INTERVAL, interval, strlen(interval) + 1);
} }
bool IndicatorSensor::getMetrics(meshtastic_Telemetry *measurement) bool IndicatorSensor::getMetrics(meshtastic_Telemetry *measurement)
{ {
cobs_decode_result ret; meshtastic_SensorData data = meshtastic_SensorData_init_zero;
int len = uart_read_bytes(SENSOR_PORT_NUM, buf, (SENSOR_BUF_SIZE - 1), 100 / portTICK_PERIOD_MS);
float value = 0.0; if (ringBuf.pop(data)) {
uint8_t *p_buf_start = buf;
uint8_t *p_buf_end = buf;
if (len > 0) {
while (p_buf_start < (buf + len)) {
p_buf_end = p_buf_start;
while (p_buf_end < (buf + len)) {
if (*p_buf_end == 0x00) {
break;
}
p_buf_end++;
}
// decode buf
memset(data, 0, sizeof(data));
ret = cobs_decode(data, sizeof(data), p_buf_start, p_buf_end - p_buf_start);
// LOG_DEBUG("cobs RX status:%d, len:%d, type:0x%x ", ret.status, ret.out_len, data[0]); switch (data.type) {
case meshtastic_MessageType_SCD41_CO2: {
if (ret.out_len > 1 && ret.status == COBS_DECODE_OK) { // LOG_DEBUG("CO2: %.1f", value);
value = 0.0; break;
uint8_t pkt_type = data[0];
switch (pkt_type) {
case PKT_TYPE_SENSOR_SCD41_CO2: {
memcpy(&value, &data[1], sizeof(value));
// LOG_DEBUG("CO2: %.1f", value);
cmd_send(PKT_TYPE_ACK, ACK_PKT_PARA, 4);
break;
}
case PKT_TYPE_SENSOR_AHT20_TEMP: {
memcpy(&value, &data[1], sizeof(value));
// LOG_DEBUG("Temp: %.1f", value);
cmd_send(PKT_TYPE_ACK, ACK_PKT_PARA, 4);
measurement->variant.environment_metrics.has_temperature = true;
measurement->variant.environment_metrics.temperature = value;
break;
}
case PKT_TYPE_SENSOR_AHT20_HUMIDITY: {
memcpy(&value, &data[1], sizeof(value));
// LOG_DEBUG("Humidity: %.1f", value);
cmd_send(PKT_TYPE_ACK, ACK_PKT_PARA, 4);
measurement->variant.environment_metrics.has_relative_humidity = true;
measurement->variant.environment_metrics.relative_humidity = value;
break;
}
case PKT_TYPE_SENSOR_TVOC_INDEX: {
memcpy(&value, &data[1], sizeof(value));
// LOG_DEBUG("Tvoc: %.1f", value);
cmd_send(PKT_TYPE_ACK, ACK_PKT_PARA, 4);
measurement->variant.environment_metrics.has_iaq = true;
measurement->variant.environment_metrics.iaq = value;
break;
}
default:
break;
}
}
p_buf_start = p_buf_end + 1; // next message
} }
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 true;
} }
return false; return false;
} }
size_t IndicatorSensor::stuff_buffer(meshtastic_SensorData message)
{
return ringBuf.push(message) ? 1 : 0;
}
#endif #endif

View File

@ -2,8 +2,10 @@
#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR #if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
#include "../mesh/generated/meshtastic/interdevice.pb.h"
#include "../mesh/generated/meshtastic/telemetry.pb.h" #include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "TelemetrySensor.h" #include "TelemetrySensor.h"
#include <RingBuf.h>
class IndicatorSensor : public TelemetrySensor class IndicatorSensor : public TelemetrySensor
{ {
@ -14,6 +16,10 @@ class IndicatorSensor : public TelemetrySensor
IndicatorSensor(); IndicatorSensor();
virtual int32_t runOnce() override; virtual int32_t runOnce() override;
virtual bool getMetrics(meshtastic_Telemetry *measurement) override; virtual bool getMetrics(meshtastic_Telemetry *measurement) override;
size_t stuff_buffer(meshtastic_SensorData message);
private:
RingBuf<meshtastic_SensorData, 16> ringBuf;
}; };
#endif #endif

View File

@ -1,129 +0,0 @@
#include "cobs.h"
#include <stdlib.h>
#ifdef SENSECAP_INDICATOR
cobs_encode_result cobs_encode(uint8_t *dst_buf_ptr, size_t dst_buf_len, const uint8_t *src_ptr, size_t src_len)
{
cobs_encode_result result = {0, COBS_ENCODE_OK};
if (!dst_buf_ptr || !src_ptr) {
result.status = COBS_ENCODE_NULL_POINTER;
return result;
}
const uint8_t *src_read_ptr = src_ptr;
const uint8_t *src_end_ptr = src_read_ptr + src_len;
uint8_t *dst_buf_start_ptr = dst_buf_ptr;
uint8_t *dst_buf_end_ptr = dst_buf_start_ptr + dst_buf_len;
uint8_t *dst_code_write_ptr = dst_buf_ptr;
uint8_t *dst_write_ptr = dst_code_write_ptr + 1;
uint8_t search_len = 1;
if (src_len != 0) {
for (;;) {
if (dst_write_ptr >= dst_buf_end_ptr) {
result.status = (cobs_encode_status)(result.status | (cobs_encode_status)COBS_ENCODE_OUT_BUFFER_OVERFLOW);
break;
}
uint8_t src_byte = *src_read_ptr++;
if (src_byte == 0) {
*dst_code_write_ptr = search_len;
dst_code_write_ptr = dst_write_ptr++;
search_len = 1;
if (src_read_ptr >= src_end_ptr) {
break;
}
} else {
*dst_write_ptr++ = src_byte;
search_len++;
if (src_read_ptr >= src_end_ptr) {
break;
}
if (search_len == 0xFF) {
*dst_code_write_ptr = search_len;
dst_code_write_ptr = dst_write_ptr++;
search_len = 1;
}
}
}
}
if (dst_code_write_ptr >= dst_buf_end_ptr) {
result.status = (cobs_encode_status)(result.status | (cobs_encode_status)COBS_ENCODE_OUT_BUFFER_OVERFLOW);
dst_write_ptr = dst_buf_end_ptr;
} else {
*dst_code_write_ptr = search_len;
}
result.out_len = dst_write_ptr - dst_buf_start_ptr;
return result;
}
cobs_decode_result cobs_decode(uint8_t *dst_buf_ptr, size_t dst_buf_len, const uint8_t *src_ptr, size_t src_len)
{
cobs_decode_result result = {0, COBS_DECODE_OK};
if (!dst_buf_ptr || !src_ptr) {
result.status = COBS_DECODE_NULL_POINTER;
return result;
}
const uint8_t *src_read_ptr = src_ptr;
const uint8_t *src_end_ptr = src_read_ptr + src_len;
uint8_t *dst_buf_start_ptr = dst_buf_ptr;
const uint8_t *dst_buf_end_ptr = dst_buf_start_ptr + dst_buf_len;
uint8_t *dst_write_ptr = dst_buf_ptr;
if (src_len != 0) {
for (;;) {
uint8_t len_code = *src_read_ptr++;
if (len_code == 0) {
result.status = (cobs_decode_status)(result.status | (cobs_decode_status)COBS_DECODE_ZERO_BYTE_IN_INPUT);
break;
}
len_code--;
size_t remaining_bytes = src_end_ptr - src_read_ptr;
if (len_code > remaining_bytes) {
result.status = (cobs_decode_status)(result.status | (cobs_decode_status)COBS_DECODE_INPUT_TOO_SHORT);
len_code = remaining_bytes;
}
remaining_bytes = dst_buf_end_ptr - dst_write_ptr;
if (len_code > remaining_bytes) {
result.status = (cobs_decode_status)(result.status | (cobs_decode_status)COBS_DECODE_OUT_BUFFER_OVERFLOW);
len_code = remaining_bytes;
}
for (uint8_t i = len_code; i != 0; i--) {
uint8_t src_byte = *src_read_ptr++;
if (src_byte == 0) {
result.status = (cobs_decode_status)(result.status | (cobs_decode_status)COBS_DECODE_ZERO_BYTE_IN_INPUT);
}
*dst_write_ptr++ = src_byte;
}
if (src_read_ptr >= src_end_ptr) {
break;
}
if (len_code != 0xFE) {
if (dst_write_ptr >= dst_buf_end_ptr) {
result.status = (cobs_decode_status)(result.status | (cobs_decode_status)COBS_DECODE_OUT_BUFFER_OVERFLOW);
break;
}
*dst_write_ptr++ = 0;
}
}
}
result.out_len = dst_write_ptr - dst_buf_start_ptr;
return result;
}
#endif

View File

@ -1,75 +0,0 @@
#ifndef COBS_H_
#define COBS_H_
#include "configuration.h"
#ifdef SENSECAP_INDICATOR
#include <stdint.h>
#include <stdlib.h>
#define COBS_ENCODE_DST_BUF_LEN_MAX(SRC_LEN) ((SRC_LEN) + (((SRC_LEN) + 253u) / 254u))
#define COBS_DECODE_DST_BUF_LEN_MAX(SRC_LEN) (((SRC_LEN) == 0) ? 0u : ((SRC_LEN)-1u))
#define COBS_ENCODE_SRC_OFFSET(SRC_LEN) (((SRC_LEN) + 253u) / 254u)
typedef enum {
COBS_ENCODE_OK = 0x00,
COBS_ENCODE_NULL_POINTER = 0x01,
COBS_ENCODE_OUT_BUFFER_OVERFLOW = 0x02
} cobs_encode_status;
typedef struct {
size_t out_len;
cobs_encode_status status;
} cobs_encode_result;
typedef enum {
COBS_DECODE_OK = 0x00,
COBS_DECODE_NULL_POINTER = 0x01,
COBS_DECODE_OUT_BUFFER_OVERFLOW = 0x02,
COBS_DECODE_ZERO_BYTE_IN_INPUT = 0x04,
COBS_DECODE_INPUT_TOO_SHORT = 0x08
} cobs_decode_status;
typedef struct {
size_t out_len;
cobs_decode_status status;
} cobs_decode_result;
#ifdef __cplusplus
extern "C" {
#endif
/* COBS-encode a string of input bytes.
*
* dst_buf_ptr: The buffer into which the result will be written
* dst_buf_len: Length of the buffer into which the result will be written
* src_ptr: The byte string to be encoded
* src_len Length of the byte string to be encoded
*
* returns: A struct containing the success status of the encoding
* operation and the length of the result (that was written to
* dst_buf_ptr)
*/
cobs_encode_result cobs_encode(uint8_t *dst_buf_ptr, size_t dst_buf_len, const uint8_t *src_ptr, size_t src_len);
/* Decode a COBS byte string.
*
* dst_buf_ptr: The buffer into which the result will be written
* dst_buf_len: Length of the buffer into which the result will be written
* src_ptr: The byte string to be decoded
* src_len Length of the byte string to be decoded
*
* returns: A struct containing the success status of the decoding
* operation and the length of the result (that was written to
* dst_buf_ptr)
*/
cobs_decode_result cobs_decode(uint8_t *dst_buf_ptr, size_t dst_buf_len, const uint8_t *src_ptr, size_t src_len);
#ifdef __cplusplus
} /* extern "C" */
#endif
#endif /* SENSECAP_INDICATOR */
#endif /* COBS_H_ */

View File

@ -9,7 +9,7 @@ board_check = true
board_build.partitions = default_8MB.csv board_build.partitions = default_8MB.csv
upload_protocol = esptool upload_protocol = esptool
build_flags = ${esp32_base.build_flags} build_flags = ${esp32s3_base.build_flags}
-Ivariants/seeed-sensecap-indicator -Ivariants/seeed-sensecap-indicator
-DSENSECAP_INDICATOR -DSENSECAP_INDICATOR
-DCONFIG_ARDUHAL_LOG_COLORS -DCONFIG_ARDUHAL_LOG_COLORS
@ -27,7 +27,7 @@ lib_deps = ${esp32s3_base.lib_deps}
https://github.com/mverch67/LovyanGFX/archive/4c76238c1344162a234ae917b27651af146d6fb2.zip https://github.com/mverch67/LovyanGFX/archive/4c76238c1344162a234ae917b27651af146d6fb2.zip
earlephilhower/ESP8266Audio@^1.9.9 earlephilhower/ESP8266Audio@^1.9.9
earlephilhower/ESP8266SAM@^1.0.1 earlephilhower/ESP8266SAM@^1.0.1
locoduino/RingBuffer@^1.0.5
[env:seeed-sensecap-indicator-tft] [env:seeed-sensecap-indicator-tft]
extends = env:seeed-sensecap-indicator extends = env:seeed-sensecap-indicator