From 6217e97c4168cf1e1b7304ba24a430b723ca9098 Mon Sep 17 00:00:00 2001 From: Tom Fifield Date: Sun, 8 Sep 2024 09:09:01 +0800 Subject: [PATCH 1/9] Add support for AG3352 and fix AG3335 support AG33352 is a Mediatek/Airoha GPS/GLONASS/Galileo/BeiDou receiver. Patch adds relevant detection and setup code. Thanks to Bluebrolly and kongduino for providing the relevant information and testing. This patch also fixes support for the A3335, which is a related chip. The setup and detection code now works as tested on a real life T-1000E! Thanks to @gpsfan for the guidance. --- src/gps/GPS.cpp | 22 ++++++++++++---------- src/gps/GPS.h | 5 +++-- 2 files changed, 15 insertions(+), 12 deletions(-) diff --git a/src/gps/GPS.cpp b/src/gps/GPS.cpp index b5e1991ae..7e5207f5e 100644 --- a/src/gps/GPS.cpp +++ b/src/gps/GPS.cpp @@ -505,18 +505,18 @@ bool GPS::setup() delay(250); _serial_gps->write("$CFGMSG,6,1,0\r\n"); delay(250); - } else if (gnssModel == GNSS_MODEL_AG3335) { + } else if (gnssModel == GNSS_MODEL_AG3335 || gnssModel == GNSS_MODEL_AG3352) { _serial_gps->write("$PAIR066,1,0,1,0,0,1*3B\r\n"); // Enable GPS+GALILEO+NAVIC // Configure NMEA (sentences will output once per fix) - _serial_gps->write("$PAIR062,0,0*3F\r\n"); // GGA ON + _serial_gps->write("$PAIR062,0,1*3F\r\n"); // GGA ON _serial_gps->write("$PAIR062,1,0*3F\r\n"); // GLL OFF - _serial_gps->write("$PAIR062,2,1*3D\r\n"); // GSA ON + _serial_gps->write("$PAIR062,2,0*3C\r\n"); // GSA OFF _serial_gps->write("$PAIR062,3,0*3D\r\n"); // GSV OFF - _serial_gps->write("$PAIR062,4,0*3B\r\n"); // RMC ON + _serial_gps->write("$PAIR062,4,1*3B\r\n"); // RMC ON _serial_gps->write("$PAIR062,5,0*3B\r\n"); // VTG OFF - _serial_gps->write("$PAIR062,6,1*39\r\n"); // ZDA ON + _serial_gps->write("$PAIR062,6,0*38\r\n"); // ZDA ON delay(250); _serial_gps->write("$PAIR513*3D\r\n"); // save configuration @@ -1204,9 +1204,6 @@ GnssModel_t GPS::probe(int serialSpeed) _serial_gps->updateBaudRate(serialSpeed); } #endif -#ifdef GNSS_AIROHA - return GNSS_MODEL_AG3335; -#endif memset(&info, 0, sizeof(struct uBloxGnssModelInfo)); uint8_t buffer[768] = {0}; @@ -1225,7 +1222,12 @@ GnssModel_t GPS::probe(int serialSpeed) PROBE_SIMPLE("ATGM332D", "$PCAS06,1*1A", "$GPTXT,01,01,02,HW=ATGM332D", GNSS_MODEL_ATGM336H, 500); /* Airoha (Mediatek) AG3335A/M/S, A3352Q, Quectel L89 2.0, SimCom SIM65M */ - PROBE_SIMPLE("AG3335", "PAIR020*38", "$PAIR020,AG3335", GNSS_MODEL_AG3335, 500); + _serial_gps->write("$PAIR062,2,0*3C\r\n"); // GSA OFF to reduce volume + _serial_gps->write("$PAIR062,3,0*3D\r\n"); // GSV OFF to reduce volume + _serial_gps->write("$PAIR513*3D\r\n"); // save configuration + PROBE_SIMPLE("AG3335", "$PAIR021*39", "$PAIR021,AG3335", GNSS_MODEL_AG3335, 500); + PROBE_SIMPLE("AG3352", "$PAIR021*39", "$PAIR021,AG3352", GNSS_MODEL_AG3352, 500); + PROBE_SIMPLE("LC86", "$PQTMVERNO*58", "$PQTMVERNO,LC86", GNSS_MODEL_AG3352, 500); PROBE_SIMPLE("L76K", "$PCAS06,0*1B", "$GPTXT,01,01,02,SW=", GNSS_MODEL_MTK, 500); @@ -1802,4 +1804,4 @@ void GPS::toggleGpsMode() enable(); } } -#endif // Exclude GPS \ No newline at end of file +#endif // Exclude GPS diff --git a/src/gps/GPS.h b/src/gps/GPS.h index c0e9fb8b6..c2e660a49 100644 --- a/src/gps/GPS.h +++ b/src/gps/GPS.h @@ -30,7 +30,8 @@ typedef enum { GNSS_MODEL_UC6580, GNSS_MODEL_UNKNOWN, GNSS_MODEL_MTK_L76B, - GNSS_MODEL_AG3335 + GNSS_MODEL_AG3335, + GNSS_MODEL_AG3352 } GnssModel_t; typedef enum { @@ -310,4 +311,4 @@ class GPS : private concurrency::OSThread }; extern GPS *gps; -#endif // Exclude GPS \ No newline at end of file +#endif // Exclude GPS From ebe1b40bee4e7d4bcb332e91a5cb7f072ed2f662 Mon Sep 17 00:00:00 2001 From: Tom Fifield Date: Mon, 9 Sep 2024 09:28:04 +0800 Subject: [PATCH 2/9] If GPS sleepTime is Zero, don't sleep. At the moment if the result of sleepTime calculations comes out to zero, we put the GPS into HARDSLEEP (losing all its status) and then immediately make it ACTIVE again. This patch avoids that toga. fixes https://github.com/meshtastic/firmware/issues/4657 --- src/gps/GPS.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/gps/GPS.cpp b/src/gps/GPS.cpp index b5e1991ae..46c76c4ae 100644 --- a/src/gps/GPS.cpp +++ b/src/gps/GPS.cpp @@ -1019,7 +1019,7 @@ void GPS::down() LOG_DEBUG("%us until next search\n", sleepTime / 1000); // If update interval less than 10 seconds, no attempt to sleep - if (updateInterval <= 10 * 1000UL) + if (updateInterval <= 10 * 1000UL || sleepTime == 0) setPowerState(GPS_IDLE); else { From fabd6b0d6fbd6781d80207167a99683fe38d943b Mon Sep 17 00:00:00 2001 From: thebentern <9000580+thebentern@users.noreply.github.com> Date: Mon, 9 Sep 2024 02:54:25 +0000 Subject: [PATCH 3/9] [create-pull-request] automated change --- version.properties | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/version.properties b/version.properties index 95d3d2538..69c478482 100644 --- a/version.properties +++ b/version.properties @@ -1,4 +1,4 @@ [VERSION] major = 2 minor = 5 -build = 0 +build = 1 From dacb452d47859db93ca8d3e90732ac8cf2437b01 Mon Sep 17 00:00:00 2001 From: David <2941290+dhskinner@users.noreply.github.com> Date: Mon, 9 Sep 2024 22:16:58 +1000 Subject: [PATCH 4/9] Bugfix (#4660) --- src/input/cardKbI2cImpl.cpp | 4 ++-- .../heltec_wireless_tracker/variant.cpp | 13 ++++++++++--- 2 files changed, 12 insertions(+), 5 deletions(-) diff --git a/src/input/cardKbI2cImpl.cpp b/src/input/cardKbI2cImpl.cpp index 1bff49475..8aaebcb45 100644 --- a/src/input/cardKbI2cImpl.cpp +++ b/src/input/cardKbI2cImpl.cpp @@ -9,7 +9,7 @@ CardKbI2cImpl::CardKbI2cImpl() : KbI2cBase("cardKB") {} void CardKbI2cImpl::init() { -#ifndef ARCH_PORTDUINO +#if !MESHTASTIC_EXCLUDE_I2C && !defined(ARCH_PORTDUINO) if (cardkb_found.address == 0x00) { LOG_DEBUG("Rescanning for I2C keyboard\n"); uint8_t i2caddr_scan[] = {CARDKB_ADDR, TDECK_KB_ADDR, BBQ10_KB_ADDR}; @@ -57,4 +57,4 @@ void CardKbI2cImpl::init() } #endif inputBroker->registerSource(this); -} +} \ No newline at end of file diff --git a/src/platform/extra_variants/heltec_wireless_tracker/variant.cpp b/src/platform/extra_variants/heltec_wireless_tracker/variant.cpp index 84264ef58..0a19a9c3b 100644 --- a/src/platform/extra_variants/heltec_wireless_tracker/variant.cpp +++ b/src/platform/extra_variants/heltec_wireless_tracker/variant.cpp @@ -10,10 +10,14 @@ void lateInitVariant() { // LOG_DEBUG("Heltec tracker initVariant\n"); -#ifdef VEXT_ENABLE - GpioPin *hwEnable = new GpioHwPin(VEXT_ENABLE); - GpioVirtPin *virtGpsEnable = gps ? gps->enablePin : new GpioVirtPin(); +#ifndef MESHTASTIC_EXCLUDE_GPS + GpioVirtPin *virtGpsEnable = gps ? gps->enablePin : new GpioVirtPin(); +#else + GpioVirtPin *virtGpsEnable = new GpioVirtPin(); +#endif + +#ifndef MESHTASTIC_EXCLUDE_SCREEN // On this board we are actually using the backlightEnable signal to already be controlling a physical enable to the // display controller. But we'd _ALSO_ like to have that signal drive a virtual GPIO. So nest it as needed. GpioVirtPin *virtScreenEnable = new GpioVirtPin(); @@ -25,8 +29,11 @@ void lateInitVariant() // Assume screen is initially powered splitter->set(true); } +#endif +#if defined(VEXT_ENABLE) && (!defined(MESHTASTIC_EXCLUDE_GPS) || !defined(MESHTASTIC_EXCLUDE_SCREEN)) // If either the GPS or the screen is on, turn on the external power regulator + GpioPin *hwEnable = new GpioHwPin(VEXT_ENABLE); new GpioBinaryTransformer(virtGpsEnable, virtScreenEnable, hwEnable, GpioBinaryTransformer::Or); #endif } From e9d55de3cb7e5b028a33b82146394d948a1d73ce Mon Sep 17 00:00:00 2001 From: Tom Fifield Date: Mon, 9 Sep 2024 20:54:11 +0800 Subject: [PATCH 5/9] Fix out-of-bound array access in T1000X Sensor (#4663) if u8i == 135, then u8i++ runs, the loop exits since u8i == 136, then value for u8i is 136 after the for loop. then in the next line, ntc_res2[u8i] will read past the end of the array --- src/modules/Telemetry/Sensor/T1000xSensor.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/Telemetry/Sensor/T1000xSensor.cpp b/src/modules/Telemetry/Sensor/T1000xSensor.cpp index 4079d8ae3..4772aeb9e 100644 --- a/src/modules/Telemetry/Sensor/T1000xSensor.cpp +++ b/src/modules/Telemetry/Sensor/T1000xSensor.cpp @@ -95,7 +95,7 @@ float T1000xSensor::getTemp() Vout = ntc_vot; Rt = (HEATER_NTC_RP * vcc_vot) / Vout - HEATER_NTC_RP; - for (u8i = 0; u8i < 136; u8i++) { + for (u8i = 0; u8i < 135; u8i++) { if (Rt >= ntc_res2[u8i]) { break; } From dc8cc122a62242536021a2fbbe86d84928a693b6 Mon Sep 17 00:00:00 2001 From: Tom Fifield Date: Mon, 9 Sep 2024 22:20:21 +0800 Subject: [PATCH 6/9] Add explicit to JSONValue constructors (#4665) --- src/serialization/JSONValue.h | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/src/serialization/JSONValue.h b/src/serialization/JSONValue.h index 0380d324b..16d53e89f 100644 --- a/src/serialization/JSONValue.h +++ b/src/serialization/JSONValue.h @@ -40,15 +40,15 @@ class JSONValue public: JSONValue(/*NULL*/); - JSONValue(const char *m_char_value); - JSONValue(const std::string &m_string_value); - JSONValue(bool m_bool_value); - JSONValue(double m_number_value); - JSONValue(int 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); + explicit JSONValue(const char *m_char_value); + explicit JSONValue(const std::string &m_string_value); + explicit JSONValue(bool m_bool_value); + explicit JSONValue(double m_number_value); + explicit JSONValue(int m_integer_value); + explicit JSONValue(unsigned int m_integer_value); + explicit JSONValue(const JSONArray &m_array_value); + explicit JSONValue(const JSONObject &m_object_value); + explicit JSONValue(const JSONValue &m_source); ~JSONValue(); bool IsNull() const; From 2f9dcee954ed9568aa7bc7fee163670598aba901 Mon Sep 17 00:00:00 2001 From: GUVWAF Date: Mon, 9 Sep 2024 19:13:00 +0200 Subject: [PATCH 7/9] Fix size calculation of route/SNR array --- src/modules/TraceRouteModule.cpp | 8 ++++---- src/modules/TraceRouteModule.h | 2 ++ 2 files changed, 6 insertions(+), 4 deletions(-) diff --git a/src/modules/TraceRouteModule.cpp b/src/modules/TraceRouteModule.cpp index dd3d0b4f9..23b4f1ccf 100644 --- a/src/modules/TraceRouteModule.cpp +++ b/src/modules/TraceRouteModule.cpp @@ -53,7 +53,7 @@ void TraceRouteModule::insertUnknownHops(meshtastic_MeshPacket &p, meshtastic_Ro uint8_t hopsTaken = p.hop_start - p.hop_limit; int8_t diff = hopsTaken - *route_count; for (uint8_t i = 0; i < diff; i++) { - if (*route_count < sizeof(*route) / sizeof(route[0])) { + if (*route_count < ROUTE_SIZE) { route[*route_count] = NODENUM_BROADCAST; // This will represent an unknown hop *route_count += 1; } @@ -61,7 +61,7 @@ void TraceRouteModule::insertUnknownHops(meshtastic_MeshPacket &p, meshtastic_Ro // Add unknown SNR values if necessary diff = *route_count - *snr_count; for (uint8_t i = 0; i < diff; i++) { - if (*snr_count < sizeof(*snr_list) / sizeof(snr_list[0])) { + if (*snr_count < ROUTE_SIZE) { snr_list[*snr_count] = INT8_MIN; // This will represent an unknown SNR *snr_count += 1; } @@ -89,7 +89,7 @@ void TraceRouteModule::appendMyIDandSNR(meshtastic_RouteDiscovery *updated, floa snr_list = updated->snr_back; } - if (*snr_count < sizeof(*snr_list) / sizeof(snr_list[0])) { + if (*snr_count < ROUTE_SIZE) { snr_list[*snr_count] = (int8_t)(snr * 4); // Convert SNR to 1 byte *snr_count += 1; } @@ -97,7 +97,7 @@ void TraceRouteModule::appendMyIDandSNR(meshtastic_RouteDiscovery *updated, floa return; // Length of route array can normally not be exceeded due to the max. hop_limit of 7 - if (*route_count < sizeof(*route) / sizeof(route[0])) { + if (*route_count < ROUTE_SIZE) { route[*route_count] = myNodeInfo.my_node_num; *route_count += 1; } else { diff --git a/src/modules/TraceRouteModule.h b/src/modules/TraceRouteModule.h index fe69300de..afe2b3871 100644 --- a/src/modules/TraceRouteModule.h +++ b/src/modules/TraceRouteModule.h @@ -1,6 +1,8 @@ #pragma once #include "ProtobufModule.h" +#define ROUTE_SIZE sizeof(((meshtastic_RouteDiscovery *)0)->route) / sizeof(((meshtastic_RouteDiscovery *)0)->route[0]) + /** * A module that traces the route to a certain destination node */ From 106dab23db826b52873bead8a88f7a1bab60c8fb Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Mon, 9 Sep 2024 14:20:14 -0500 Subject: [PATCH 8/9] Revert "Changes by create-pull-request action" (#4671) --- version.properties | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/version.properties b/version.properties index 69c478482..95d3d2538 100644 --- a/version.properties +++ b/version.properties @@ -1,4 +1,4 @@ [VERSION] major = 2 minor = 5 -build = 1 +build = 0 From 4ed12bf21d43dcb40368025e96dea414f8ab1f9b Mon Sep 17 00:00:00 2001 From: GUVWAF <78759985+GUVWAF@users.noreply.github.com> Date: Mon, 9 Sep 2024 21:22:32 +0200 Subject: [PATCH 9/9] Try fix repeatedly getting a new NodeNum (#4670) --- src/mesh/NodeDB.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/mesh/NodeDB.cpp b/src/mesh/NodeDB.cpp index 06180310a..5244fd10f 100644 --- a/src/mesh/NodeDB.cpp +++ b/src/mesh/NodeDB.cpp @@ -121,6 +121,8 @@ NodeDB::NodeDB() owner.hw_model = HW_VENDOR; // Ensure user (nodeinfo) role is set to whatever we're configured to owner.role = config.device.role; + // Ensure macaddr is set to our macaddr as it will be copied in our info below + memcpy(owner.macaddr, ourMacAddr, sizeof(owner.macaddr)); // Include our owner in the node db under our nodenum meshtastic_NodeInfoLite *info = getOrCreateMeshNode(getNodeNum()); @@ -1194,4 +1196,4 @@ void recordCriticalError(meshtastic_CriticalErrorCode code, uint32_t address, co LOG_ERROR("A critical failure occurred, portduino is exiting..."); exit(2); #endif -} +} \ No newline at end of file