From a5b79528b35a0e7212440574e75d86c97787bc25 Mon Sep 17 00:00:00 2001 From: beegee-tokyo Date: Mon, 9 Sep 2024 11:56:37 +0800 Subject: [PATCH 01/88] Add RAK4631 Ethernet Gateway with working JSON output to MQTT --- platformio.ini | 3 +- src/mqtt/MQTT.cpp | 12 +- src/serialization/MeshPacketSerializer.cpp | 4 +- .../MeshPacketSerializer_nRF52.cpp | 325 ++++++++++++++++++ variants/rak4631_mqtt_json/platformio.ini | 58 ++++ variants/rak4631_mqtt_json/variant.cpp | 45 +++ variants/rak4631_mqtt_json/variant.h | 273 +++++++++++++++ 7 files changed, 712 insertions(+), 8 deletions(-) create mode 100644 src/serialization/MeshPacketSerializer_nRF52.cpp create mode 100644 variants/rak4631_mqtt_json/platformio.ini create mode 100644 variants/rak4631_mqtt_json/variant.cpp create mode 100644 variants/rak4631_mqtt_json/variant.h diff --git a/platformio.ini b/platformio.ini index 87eb0afb7..a39de33c1 100644 --- a/platformio.ini +++ b/platformio.ini @@ -2,7 +2,7 @@ ; https://docs.platformio.org/page/projectconf.html [platformio] -default_envs = tbeam +;default_envs = tbeam ;default_envs = pico ;default_envs = tbeam-s3-core ;default_envs = tbeam0.7 @@ -29,6 +29,7 @@ default_envs = tbeam ;default_envs = meshtastic-dr-dev ;default_envs = m5stack-coreink ;default_envs = rak4631 +default_envs = rak4631_mqtt_json ;default_envs = rak2560 ;default_envs = rak10701 ;default_envs = wio-e5 diff --git a/src/mqtt/MQTT.cpp b/src/mqtt/MQTT.cpp index d14c7a923..63bdd5bba 100644 --- a/src/mqtt/MQTT.cpp +++ b/src/mqtt/MQTT.cpp @@ -379,13 +379,13 @@ void MQTT::sendSubscriptions() std::string topic = cryptTopic + channels.getGlobalId(i) + "/+"; LOG_INFO("Subscribing to %s\n", topic.c_str()); pubSub.subscribe(topic.c_str(), 1); // FIXME, is QOS 1 right? -#ifndef ARCH_NRF52 // JSON is not supported on nRF52, see issue #2804 +// #ifndef ARCH_NRF52 // JSON is not supported on nRF52, see issue #2804 ### Fixed by using ArduinoJSON ### if (moduleConfig.mqtt.json_enabled == true) { std::string topicDecoded = jsonTopic + channels.getGlobalId(i) + "/+"; LOG_INFO("Subscribing to %s\n", topicDecoded.c_str()); pubSub.subscribe(topicDecoded.c_str(), 1); // FIXME, is QOS 1 right? } -#endif // ARCH_NRF52 +// #endif // ARCH_NRF52 } } #if !MESHTASTIC_EXCLUDE_PKI @@ -480,7 +480,7 @@ void MQTT::publishQueuedMessages() publish(topic.c_str(), bytes, numBytes, false); -#ifndef ARCH_NRF52 // JSON is not supported on nRF52, see issue #2804 +// #ifndef ARCH_NRF52 // JSON is not supported on nRF52, see issue #2804 ### Fixed by using ArduinoJson ### if (moduleConfig.mqtt.json_enabled) { // handle json topic auto jsonString = MeshPacketSerializer::JsonSerialize(env->packet); @@ -496,7 +496,7 @@ void MQTT::publishQueuedMessages() publish(topicJson.c_str(), jsonString.c_str(), false); } } -#endif // ARCH_NRF52 +// #endif // ARCH_NRF52 mqttPool.release(env); } } @@ -562,7 +562,7 @@ void MQTT::onSend(const meshtastic_MeshPacket &mp, const meshtastic_MeshPacket & publish(topic.c_str(), bytes, numBytes, false); -#ifndef ARCH_NRF52 // JSON is not supported on nRF52, see issue #2804 +// #ifndef ARCH_NRF52 // JSON is not supported on nRF52, see issue #2804 ### Fixed by using ArduinoJson ### if (moduleConfig.mqtt.json_enabled) { // handle json topic auto jsonString = MeshPacketSerializer::JsonSerialize((meshtastic_MeshPacket *)&mp_decoded); @@ -573,7 +573,7 @@ void MQTT::onSend(const meshtastic_MeshPacket &mp, const meshtastic_MeshPacket & publish(topicJson.c_str(), jsonString.c_str(), false); } } -#endif // ARCH_NRF52 +// #endif // ARCH_NRF52 } else { LOG_INFO("MQTT not connected, queueing packet\n"); if (mqttQueue.numFree() == 0) { diff --git a/src/serialization/MeshPacketSerializer.cpp b/src/serialization/MeshPacketSerializer.cpp index e00dde024..227205d84 100644 --- a/src/serialization/MeshPacketSerializer.cpp +++ b/src/serialization/MeshPacketSerializer.cpp @@ -1,3 +1,4 @@ +#ifndef NRF52_USE_JSON #include "MeshPacketSerializer.h" #include "JSON.h" #include "NodeDB.h" @@ -353,4 +354,5 @@ std::string MeshPacketSerializer::JsonSerializeEncrypted(const meshtastic_MeshPa delete value; return jsonStr; -} \ No newline at end of file +} +#endif \ No newline at end of file diff --git a/src/serialization/MeshPacketSerializer_nRF52.cpp b/src/serialization/MeshPacketSerializer_nRF52.cpp new file mode 100644 index 000000000..7302e0915 --- /dev/null +++ b/src/serialization/MeshPacketSerializer_nRF52.cpp @@ -0,0 +1,325 @@ +#ifdef NRF52_USE_JSON +#warning 'Using nRF52 Serializer' + +#include "MeshPacketSerializer.h" +#include "ArduinoJson.h" +#include "NodeDB.h" +#include "mesh/generated/meshtastic/mqtt.pb.h" +#include "mesh/generated/meshtastic/telemetry.pb.h" +#include "modules/RoutingModule.h" +#include +#include +#include "mesh/generated/meshtastic/remote_hardware.pb.h" + +StaticJsonDocument<512> jsonObj; +// StaticJsonDocument<512> msgPayload; + +std::string MeshPacketSerializer::JsonSerialize(const meshtastic_MeshPacket *mp, bool shouldLog) +{ + // the created jsonObj is immutable after creation, so + // we need to do the heavy lifting before assembling it. + std::string msgType; + // JSONObject jsonObj; + jsonObj.clear(); + + if (mp->which_payload_variant == meshtastic_MeshPacket_decoded_tag) { + // JSONObject msgPayload; + switch (mp->decoded.portnum) { + case meshtastic_PortNum_TEXT_MESSAGE_APP: { + msgType = "text"; + // convert bytes to string + if (shouldLog) + LOG_DEBUG("got text message of size %u\n", mp->decoded.payload.size); + + char payloadStr[(mp->decoded.payload.size) + 1]; + memcpy(payloadStr, mp->decoded.payload.bytes, mp->decoded.payload.size); + payloadStr[mp->decoded.payload.size] = 0; // null terminated string + // check if this is a JSON payload + StaticJsonDocument<512> text_doc; + DeserializationError error = deserializeJson(text_doc, payloadStr); + if (error) { + // if it isn't, then we need to create a json object + // with the string as the value + if (shouldLog) + LOG_INFO("text message payload is of type plaintext\n"); + jsonObj["payload"]["text"] = payloadStr; + // jsonObj["payload"] = msgPayload; + } else { + // if it is, then we can just use the json object + if (shouldLog) + LOG_INFO("text message payload is of type json\n"); + jsonObj["payload"] = text_doc; + } + break; + } + case meshtastic_PortNum_TELEMETRY_APP: { + msgType = "telemetry"; + meshtastic_Telemetry scratch; + meshtastic_Telemetry *decoded = NULL; + memset(&scratch, 0, sizeof(scratch)); + 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) { + jsonObj["payload"]["battery_level"] = (unsigned int)decoded->variant.device_metrics.battery_level; + jsonObj["payload"]["voltage"] = decoded->variant.device_metrics.voltage; + jsonObj["payload"]["channel_utilization"] = decoded->variant.device_metrics.channel_utilization; + jsonObj["payload"]["air_util_tx"] = decoded->variant.device_metrics.air_util_tx; + jsonObj["payload"]["uptime_seconds"] = (unsigned int)decoded->variant.device_metrics.uptime_seconds; + } else if (decoded->which_variant == meshtastic_Telemetry_environment_metrics_tag) { + jsonObj["payload"]["temperature"] = decoded->variant.environment_metrics.temperature; + jsonObj["payload"]["relative_humidity"] = decoded->variant.environment_metrics.relative_humidity; + jsonObj["payload"]["barometric_pressure"] = decoded->variant.environment_metrics.barometric_pressure; + jsonObj["payload"]["gas_resistance"] = decoded->variant.environment_metrics.gas_resistance; + jsonObj["payload"]["voltage"] = decoded->variant.environment_metrics.voltage; + jsonObj["payload"]["current"] = decoded->variant.environment_metrics.current; + jsonObj["payload"]["lux"] = decoded->variant.environment_metrics.lux; + jsonObj["payload"]["white_lux"] = decoded->variant.environment_metrics.white_lux; + jsonObj["payload"]["iaq"] = (uint)decoded->variant.environment_metrics.iaq; + jsonObj["payload"]["wind_speed"] = decoded->variant.environment_metrics.wind_speed; + jsonObj["payload"]["wind_direction"] = (uint)decoded->variant.environment_metrics.wind_direction; + jsonObj["payload"]["wind_gust"] = decoded->variant.environment_metrics.wind_gust; + jsonObj["payload"]["wind_lull"] = decoded->variant.environment_metrics.wind_lull; + } else if (decoded->which_variant == meshtastic_Telemetry_air_quality_metrics_tag) { + jsonObj["payload"]["pm10"] = (unsigned int)decoded->variant.air_quality_metrics.pm10_standard; + jsonObj["payload"]["pm25"] = (unsigned int)decoded->variant.air_quality_metrics.pm25_standard; + jsonObj["payload"]["pm100"] = (unsigned int)decoded->variant.air_quality_metrics.pm100_standard; + jsonObj["payload"]["pm10_e"] = (unsigned int)decoded->variant.air_quality_metrics.pm10_environmental; + jsonObj["payload"]["pm25_e"] = (unsigned int)decoded->variant.air_quality_metrics.pm25_environmental; + jsonObj["payload"]["pm100_e"] = (unsigned int)decoded->variant.air_quality_metrics.pm100_environmental; + } else if (decoded->which_variant == meshtastic_Telemetry_power_metrics_tag) { + jsonObj["payload"]["voltage_ch1"] = decoded->variant.power_metrics.ch1_voltage; + jsonObj["payload"]["current_ch1"] = decoded->variant.power_metrics.ch1_current; + jsonObj["payload"]["voltage_ch2"] = decoded->variant.power_metrics.ch2_voltage; + jsonObj["payload"]["current_ch2"] = decoded->variant.power_metrics.ch2_current; + jsonObj["payload"]["voltage_ch3"] = decoded->variant.power_metrics.ch3_voltage; + jsonObj["payload"]["current_ch3"] = decoded->variant.power_metrics.ch3_current; + } + } else if (shouldLog) { + LOG_ERROR("Error decoding protobuf for telemetry message!\n"); + } + break; + } + case meshtastic_PortNum_NODEINFO_APP: { + msgType = "nodeinfo"; + meshtastic_User scratch; + meshtastic_User *decoded = NULL; + memset(&scratch, 0, sizeof(scratch)); + if (pb_decode_from_bytes(mp->decoded.payload.bytes, mp->decoded.payload.size, &meshtastic_User_msg, &scratch)) { + decoded = &scratch; + jsonObj["payload"]["id"] = decoded->id; + jsonObj["payload"]["longname"] = decoded->long_name; + jsonObj["payload"]["shortname"] = decoded->short_name; + jsonObj["payload"]["hardware"] = decoded->hw_model; + jsonObj["payload"]["role"] = (int)decoded->role; + } else if (shouldLog) { + LOG_ERROR("Error decoding protobuf for nodeinfo message!\n"); + } + break; + } + case meshtastic_PortNum_POSITION_APP: { + msgType = "position"; + meshtastic_Position scratch; + meshtastic_Position *decoded = NULL; + memset(&scratch, 0, sizeof(scratch)); + if (pb_decode_from_bytes(mp->decoded.payload.bytes, mp->decoded.payload.size, &meshtastic_Position_msg, &scratch)) { + decoded = &scratch; + if ((int)decoded->time) { + jsonObj["payload"]["time"] = (unsigned int)decoded->time; + } + if ((int)decoded->timestamp) { + jsonObj["payload"]["timestamp"] = (unsigned int)decoded->timestamp; + } + jsonObj["payload"]["latitude_i"] = (int)decoded->latitude_i; + jsonObj["payload"]["longitude_i"] = (int)decoded->longitude_i; + if ((int)decoded->altitude) { + jsonObj["payload"]["altitude"] = (int)decoded->altitude; + } + if ((int)decoded->ground_speed) { + jsonObj["payload"]["ground_speed"] = (unsigned int)decoded->ground_speed; + } + if (int(decoded->ground_track)) { + jsonObj["payload"]["ground_track"] = (unsigned int)decoded->ground_track; + } + if (int(decoded->sats_in_view)) { + jsonObj["payload"]["sats_in_view"] = (unsigned int)decoded->sats_in_view; + } + if ((int)decoded->PDOP) { + jsonObj["payload"]["PDOP"] = (int)decoded->PDOP; + } + if ((int)decoded->HDOP) { + jsonObj["payload"]["HDOP"] = (int)decoded->HDOP; + } + if ((int)decoded->VDOP) { + jsonObj["payload"]["VDOP"] = (int)decoded->VDOP; + } + if ((int)decoded->precision_bits) { + jsonObj["payload"]["precision_bits"] = (int)decoded->precision_bits; + } + } else if (shouldLog) { + LOG_ERROR("Error decoding protobuf for position message!\n"); + } + break; + } + case meshtastic_PortNum_WAYPOINT_APP: { + msgType = "position"; + meshtastic_Waypoint scratch; + meshtastic_Waypoint *decoded = NULL; + memset(&scratch, 0, sizeof(scratch)); + if (pb_decode_from_bytes(mp->decoded.payload.bytes, mp->decoded.payload.size, &meshtastic_Waypoint_msg, &scratch)) { + decoded = &scratch; + jsonObj["payload"]["id"] = (unsigned int)decoded->id; + jsonObj["payload"]["name"] = decoded->name; + jsonObj["payload"]["description"] = decoded->description; + jsonObj["payload"]["expire"] = (unsigned int)decoded->expire; + jsonObj["payload"]["locked_to"] = (unsigned int)decoded->locked_to; + jsonObj["payload"]["latitude_i"] = (int)decoded->latitude_i; + jsonObj["payload"]["longitude_i"] = (int)decoded->longitude_i; + } else if (shouldLog) { + LOG_ERROR("Error decoding protobuf for position message!\n"); + } + break; + } + case meshtastic_PortNum_NEIGHBORINFO_APP: { + msgType = "neighborinfo"; + meshtastic_NeighborInfo scratch; + meshtastic_NeighborInfo *decoded = NULL; + memset(&scratch, 0, sizeof(scratch)); + if (pb_decode_from_bytes(mp->decoded.payload.bytes, mp->decoded.payload.size, &meshtastic_NeighborInfo_msg, + &scratch)) { + decoded = &scratch; + jsonObj["payload"]["node_id"] = (unsigned int)decoded->node_id; + jsonObj["payload"]["node_broadcast_interval_secs"] = (unsigned int)decoded->node_broadcast_interval_secs; + jsonObj["payload"]["last_sent_by_id"] = (unsigned int)decoded->last_sent_by_id; + jsonObj["payload"]["neighbors_count"] = decoded->neighbors_count; + + JsonArray neighbors = jsonObj.createNestedArray("neighbors"); + JsonObject neighbors_0 = neighbors.createNestedObject(); + + for (uint8_t i = 0; i < decoded->neighbors_count; i++) { + neighbors_0["node_id"] = (unsigned int)decoded->neighbors[i].node_id; + neighbors_0["snr"] = (int)decoded->neighbors[i].snr; + neighbors_0.clear(); + } + } else if (shouldLog) { + LOG_ERROR("Error decoding protobuf for neighborinfo message!\n"); + } + break; + } + case meshtastic_PortNum_TRACEROUTE_APP: { + if (mp->decoded.request_id) { // Only report the traceroute response + msgType = "traceroute"; + meshtastic_RouteDiscovery scratch; + meshtastic_RouteDiscovery *decoded = NULL; + memset(&scratch, 0, sizeof(scratch)); + if (pb_decode_from_bytes(mp->decoded.payload.bytes, mp->decoded.payload.size, &meshtastic_RouteDiscovery_msg, + &scratch)) { + decoded = &scratch; + JsonArray route = jsonObj.createNestedArray("route"); + + route.add(mp->to); + for (uint8_t i = 0; i < decoded->route_count; i++) { + route.add(decoded->route[i]); + } + route.add(mp->from); // Ended at the original destination (source of response) + } else if (shouldLog) { + LOG_ERROR("Error decoding protobuf for traceroute message!\n"); + } + } + break; + } + case meshtastic_PortNum_DETECTION_SENSOR_APP: { + msgType = "detection"; + char payloadStr[(mp->decoded.payload.size) + 1]; + memcpy(payloadStr, mp->decoded.payload.bytes, mp->decoded.payload.size); + payloadStr[mp->decoded.payload.size] = 0; // null terminated string + jsonObj["payload"]["text"] = payloadStr; + break; + } + case meshtastic_PortNum_REMOTE_HARDWARE_APP: { + meshtastic_HardwareMessage scratch; + meshtastic_HardwareMessage *decoded = NULL; + memset(&scratch, 0, sizeof(scratch)); + if (pb_decode_from_bytes(mp->decoded.payload.bytes, mp->decoded.payload.size, &meshtastic_HardwareMessage_msg, + &scratch)) { + decoded = &scratch; + if (decoded->type == meshtastic_HardwareMessage_Type_GPIOS_CHANGED) { + msgType = "gpios_changed"; + jsonObj["payload"]["gpio_value"] = (unsigned int)decoded->gpio_value; + } else if (decoded->type == meshtastic_HardwareMessage_Type_READ_GPIOS_REPLY) { + msgType = "gpios_read_reply"; + jsonObj["payload"]["gpio_value"] = (unsigned int)decoded->gpio_value; + jsonObj["payload"]["gpio_mask"] = (unsigned int)decoded->gpio_mask; + } + } else if (shouldLog) { + LOG_ERROR("Error decoding protobuf for RemoteHardware message!\n"); + } + break; + } + // add more packet types here if needed + default: + break; + } + } else if (shouldLog) { + LOG_WARN("Couldn't convert encrypted payload of MeshPacket to JSON\n"); + } + + jsonObj["id"] = (unsigned int)mp->id; + jsonObj["timestamp"] = (unsigned int)mp->rx_time; + jsonObj["to"] = (unsigned int)mp->to; + jsonObj["from"] = (unsigned int)mp->from; + jsonObj["channel"] = (unsigned int)mp->channel; + jsonObj["type"] = msgType.c_str(); + jsonObj["sender"] = owner.id; + if (mp->rx_rssi != 0) + jsonObj["rssi"] = (int)mp->rx_rssi; + if (mp->rx_snr != 0) + jsonObj["snr"] = (float)mp->rx_snr; + if (mp->hop_start != 0 && mp->hop_limit <= mp->hop_start) { + jsonObj["hops_away"] = (unsigned int)(mp->hop_start - mp->hop_limit); + jsonObj["hop_start"] = (unsigned int)(mp->hop_start); + } + + // serialize and write it to the stream + + Serial.printf("serialized json message: \r\n"); + serializeJson(jsonObj, Serial); + Serial.println(""); + + std::string jsonStr = ""; + serializeJson(jsonObj, jsonStr); + + if (shouldLog) + LOG_INFO("serialized json message: %s\n", jsonStr.c_str()); + + return jsonStr; +} + +std::string MeshPacketSerializer::JsonSerializeEncrypted(const meshtastic_MeshPacket *mp) +{ + jsonObj["id"] = (unsigned int)mp->id; + jsonObj["time_ms"] = (double)millis(); + jsonObj["timestamp"] = (unsigned int)mp->rx_time; + jsonObj["to"] = (unsigned int)mp->to; + jsonObj["from"] = (unsigned int)mp->from; + jsonObj["channel"] = (unsigned int)mp->channel; + jsonObj["want_ack"] = mp->want_ack; + + if (mp->rx_rssi != 0) + jsonObj["rssi"] = (int)mp->rx_rssi; + if (mp->rx_snr != 0) + jsonObj["snr"] = (float)mp->rx_snr; + if (mp->hop_start != 0 && mp->hop_limit <= mp->hop_start) { + jsonObj["hops_away"] = (unsigned int)(mp->hop_start - mp->hop_limit); + jsonObj["hop_start"] = (unsigned int)(mp->hop_start); + } + jsonObj["size"] = (unsigned int)mp->encrypted.size; + auto encryptedStr = bytesToHex(mp->encrypted.bytes, mp->encrypted.size); + jsonObj["bytes"] = encryptedStr.c_str(); + + // serialize and write it to the stream + std::string jsonStr = ""; + serializeJson(jsonObj, jsonStr); + + return jsonStr; +} +#endif \ No newline at end of file diff --git a/variants/rak4631_mqtt_json/platformio.ini b/variants/rak4631_mqtt_json/platformio.ini new file mode 100644 index 000000000..5d459a91a --- /dev/null +++ b/variants/rak4631_mqtt_json/platformio.ini @@ -0,0 +1,58 @@ +; The very slick RAK wireless RAK 4631 / 4630 board - Unified firmware for 5005/19003, with or without OLED RAK 1921 +[env:rak4631_mqtt_json] +extends = nrf52840_base +board = wiscore_rak4631 +board_check = true +build_flags = ${nrf52840_base.build_flags} -Ivariants/rak4631_mqtt_json -D RAK_4631 + -L "${platformio.libdeps_dir}/${this.__env__}/bsec2/src/cortex-m4/fpv4-sp-d16-hard" + -DGPS_POWER_TOGGLE ; comment this line to disable triple press function on the user button to turn off gps entirely. + -DEINK_DISPLAY_MODEL=GxEPD2_213_BN + -DEINK_WIDTH=250 + -DEINK_HEIGHT=122 + -DNRF52_USE_JSON=1 +; -DMESHTASTIC_EXCLUDE_GPS=1 + -DMESHTASTIC_EXCLUDE_WIFI=1 +; -DMESHTASTIC_EXCLUDE_SCREEN=1 + -DMESHTASTIC_EXCLUDE_PKI=1 + -DMESHTASTIC_EXCLUDE_POWER_FSM=1 +build_src_filter = ${nrf52_base.build_src_filter} +<../variants/rak4631_mqtt_json> + + + +lib_deps = + ${nrf52840_base.lib_deps} + ${networking_base.lib_deps} + melopero/Melopero RV3028@^1.1.0 + https://github.com/RAKWireless/RAK13800-W5100S.git#1.0.2 + rakwireless/RAKwireless NCP5623 RGB LED library@^1.0.2 + https://github.com/meshtastic/RAK12034-BMX160.git#4821355fb10390ba8557dc43ca29a023bcfbb9d9 + bblanchon/ArduinoJson @ 6.21.4 +; If not set we will default to uploading over serial (first it forces bootloader entry by talking 1200bps to cdcacm) +; Note: as of 6/2013 the serial/bootloader based programming takes approximately 30 seconds +;upload_protocol = jlink + +; Allows programming and debug via the RAK NanoDAP as the default debugger tool for the RAK4631 (it is only $10!) +; programming time is about the same as the bootloader version. +; For information on this see the meshtastic developers documentation for "Development on the NRF52" +[env:rak4631_mqtt_json_dbg] +extends = env:rak4631 +board_level = extra + +; if the builtin version of openocd has a buggy version of semihosting, so use the external version +; platform_packages = platformio/tool-openocd@^3.1200.0 + +build_flags = + ${env:rak4631_mqtt_json.build_flags} + -D USE_SEMIHOSTING + +lib_deps = + ${env:rak4631_mqtt_json.lib_deps} + https://github.com/geeksville/Armduino-Semihosting.git#35b538fdf208c3530c1434cd099a08e486672ee4 + +; NOTE: the pyocd support for semihosting is buggy. So I switched to using the builtin platformio support for the stlink adapter which worked much better. +; However the built in openocd version in platformio has buggy support for TCP to semihosting. +; +; So I'm now trying the external openocd - but the openocd scripts for nrf52.cfg assume you are using a DAP adapter not an STLINK adapter. +; In theory I could change those scripts. But for now I'm trying going back to a DAP adapter but with the external openocd. + +upload_protocol = stlink +; eventually use platformio/tool-pyocd@^2.3600.0 instad +;upload_protocol = custom +;upload_command = pyocd flash -t nrf52840 $UPLOADERFLAGS $SOURCE \ No newline at end of file diff --git a/variants/rak4631_mqtt_json/variant.cpp b/variants/rak4631_mqtt_json/variant.cpp new file mode 100644 index 000000000..e84b60b3b --- /dev/null +++ b/variants/rak4631_mqtt_json/variant.cpp @@ -0,0 +1,45 @@ +/* + Copyright (c) 2014-2015 Arduino LLC. All right reserved. + Copyright (c) 2016 Sandeep Mistry All right reserved. + Copyright (c) 2018, Adafruit Industries (adafruit.com) + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + See the GNU Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include "variant.h" +#include "nrf.h" +#include "wiring_constants.h" +#include "wiring_digital.h" + +const uint32_t g_ADigitalPinMap[] = { + // P0 + 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, + + // P1 + 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47}; + +void initVariant() +{ + // LED1 & LED2 + pinMode(PIN_LED1, OUTPUT); + ledOff(PIN_LED1); + + pinMode(PIN_LED2, OUTPUT); + ledOff(PIN_LED2); + + // 3V3 Power Rail + pinMode(PIN_3V3_EN, OUTPUT); + digitalWrite(PIN_3V3_EN, HIGH); +} diff --git a/variants/rak4631_mqtt_json/variant.h b/variants/rak4631_mqtt_json/variant.h new file mode 100644 index 000000000..bc5541336 --- /dev/null +++ b/variants/rak4631_mqtt_json/variant.h @@ -0,0 +1,273 @@ +/* + Copyright (c) 2014-2015 Arduino LLC. All right reserved. + Copyright (c) 2016 Sandeep Mistry All right reserved. + Copyright (c) 2018, Adafruit Industries (adafruit.com) + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + See the GNU Lesser General Public License for more details. + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef _VARIANT_RAK4630_ +#define _VARIANT_RAK4630_ + +#define RAK4630 + +/** Master clock frequency */ +#define VARIANT_MCK (64000000ul) + +#define USE_LFXO // Board uses 32khz crystal for LF +// define USE_LFRC // Board uses RC for LF + +/*---------------------------------------------------------------------------- + * Headers + *----------------------------------------------------------------------------*/ + +#include "WVariant.h" + +#ifdef __cplusplus +extern "C" { +#endif // __cplusplus + +// Number of pins defined in PinDescription array +#define PINS_COUNT (48) +#define NUM_DIGITAL_PINS (48) +#define NUM_ANALOG_INPUTS (6) +#define NUM_ANALOG_OUTPUTS (0) + +// LEDs +#define PIN_LED1 (35) +#define PIN_LED2 (36) + +#define LED_BUILTIN PIN_LED1 +#define LED_CONN PIN_LED2 + +#define LED_GREEN PIN_LED1 +#define LED_BLUE PIN_LED2 + +#define LED_STATE_ON 1 // State when LED is litted + +/* + * Buttons + */ + +#define PIN_BUTTON1 9 // Pin for button on E-ink button module or IO expansion +#define BUTTON_NEED_PULLUP +#define PIN_BUTTON2 12 +#define PIN_BUTTON3 24 +#define PIN_BUTTON4 25 + +/* + * Analog pins + */ +#define PIN_A0 (5) +#define PIN_A1 (31) +#define PIN_A2 (28) +#define PIN_A3 (29) +#define PIN_A4 (30) +#define PIN_A5 (31) +#define PIN_A6 (0xff) +#define PIN_A7 (0xff) + +static const uint8_t A0 = PIN_A0; +static const uint8_t A1 = PIN_A1; +static const uint8_t A2 = PIN_A2; +static const uint8_t A3 = PIN_A3; +static const uint8_t A4 = PIN_A4; +static const uint8_t A5 = PIN_A5; +static const uint8_t A6 = PIN_A6; +static const uint8_t A7 = PIN_A7; +#define ADC_RESOLUTION 14 + +// Other pins +#define PIN_AREF (2) +#define PIN_NFC1 (9) +#define PIN_NFC2 (10) + +static const uint8_t AREF = PIN_AREF; + +/* + * Serial interfaces + */ +#define PIN_SERIAL1_RX (15) +#define PIN_SERIAL1_TX (16) + +// Connected to Jlink CDC +#define PIN_SERIAL2_RX (8) +#define PIN_SERIAL2_TX (6) + +/* + * SPI Interfaces + */ +#define SPI_INTERFACES_COUNT 2 + +#define PIN_SPI_MISO (45) +#define PIN_SPI_MOSI (44) +#define PIN_SPI_SCK (43) + +#define PIN_SPI1_MISO (29) // (0 + 29) +#define PIN_SPI1_MOSI (30) // (0 + 30) +#define PIN_SPI1_SCK (3) // (0 + 3) + +static const uint8_t SS = 42; +static const uint8_t MOSI = PIN_SPI_MOSI; +static const uint8_t MISO = PIN_SPI_MISO; +static const uint8_t SCK = PIN_SPI_SCK; + +/* + * eink display pins + */ + +#define PIN_EINK_CS (0 + 26) +#define PIN_EINK_BUSY (0 + 4) +#define PIN_EINK_DC (0 + 17) +#define PIN_EINK_RES (-1) +#define PIN_EINK_SCLK (0 + 3) +#define PIN_EINK_MOSI (0 + 30) // also called SDI + +// #define USE_EINK + +// RAKRGB +#define HAS_NCP5623 + +/* + * Wire Interfaces + */ +#define WIRE_INTERFACES_COUNT 1 + +#define PIN_WIRE_SDA (13) +#define PIN_WIRE_SCL (14) + +// QSPI Pins +#define PIN_QSPI_SCK 3 +#define PIN_QSPI_CS 26 +#define PIN_QSPI_IO0 30 +#define PIN_QSPI_IO1 29 +#define PIN_QSPI_IO2 28 +#define PIN_QSPI_IO3 2 + +// On-board QSPI Flash +#define EXTERNAL_FLASH_DEVICES IS25LP080D +#define EXTERNAL_FLASH_USE_QSPI + +/* @note RAK5005-O GPIO mapping to RAK4631 GPIO ports + RAK5005-O <-> nRF52840 + IO1 <-> P0.17 (Arduino GPIO number 17) + IO2 <-> P1.02 (Arduino GPIO number 34) + IO3 <-> P0.21 (Arduino GPIO number 21) + IO4 <-> P0.04 (Arduino GPIO number 4) + IO5 <-> P0.09 (Arduino GPIO number 9) + IO6 <-> P0.10 (Arduino GPIO number 10) + IO7 <-> P0.28 (Arduino GPIO number 28) + SW1 <-> P0.01 (Arduino GPIO number 1) + A0 <-> P0.04/AIN2 (Arduino Analog A2 + A1 <-> P0.31/AIN7 (Arduino Analog A7 + SPI_CS <-> P0.26 (Arduino GPIO number 26) + */ + +// RAK4630 LoRa module + +/* Setup of the SX1262 LoRa module ( https://docs.rakwireless.com/Product-Categories/WisBlock/RAK4631/Datasheet/ ) + +P1.10 NSS SPI NSS (Arduino GPIO number 42) +P1.11 SCK SPI CLK (Arduino GPIO number 43) +P1.12 MOSI SPI MOSI (Arduino GPIO number 44) +P1.13 MISO SPI MISO (Arduino GPIO number 45) +P1.14 BUSY BUSY signal (Arduino GPIO number 46) +P1.15 DIO1 DIO1 event interrupt (Arduino GPIO number 47) +P1.06 NRESET NRESET manual reset of the SX1262 (Arduino GPIO number 38) + +Important for successful SX1262 initialization: + +* Setup DIO2 to control the antenna switch +* Setup DIO3 to control the TCXO power supply +* Setup the SX1262 to use it's DCDC regulator and not the LDO +* RAK4630 schematics show GPIO P1.07 connected to the antenna switch, but it should not be initialized, as DIO2 will do the +control of the antenna switch + +SO GPIO 39/TXEN MAY NOT BE DEFINED FOR SUCCESSFUL OPERATION OF THE SX1262 - TG + +*/ + +#define DETECTION_SENSOR_EN 4 + +#define USE_SX1262 +#define SX126X_CS (42) +#define SX126X_DIO1 (47) +#define SX126X_BUSY (46) +#define SX126X_RESET (38) +// #define SX126X_TXEN (39) +// #define SX126X_RXEN (37) +#define SX126X_POWER_EN (37) +// DIO2 controlls an antenna switch and the TCXO voltage is controlled by DIO3 +#define SX126X_DIO2_AS_RF_SWITCH +#define SX126X_DIO3_TCXO_VOLTAGE 1.8 + +// Testing USB detection +#define NRF_APM + +// enables 3.3V periphery like GPS or IO Module +// Do not toggle this for GPS power savings +#define PIN_3V3_EN (34) + +// RAK1910 GPS module +// If using the wisblock GPS module and pluged into Port A on WisBlock base +// IO1 is hooked to PPS (pin 12 on header) = gpio 17 +// IO2 is hooked to GPS RESET = gpio 34, but it can not be used to this because IO2 is ALSO used to control 3V3_S power (1 is on). +// Therefore must be 1 to keep peripherals powered +// Power is on the controllable 3V3_S rail +// #define PIN_GPS_RESET (34) +// #define PIN_GPS_EN PIN_3V3_EN +#define PIN_GPS_PPS (17) // Pulse per second input from the GPS + +#define GPS_RX_PIN PIN_SERIAL1_RX +#define GPS_TX_PIN PIN_SERIAL1_TX + +// Define pin to enable GPS toggle (set GPIO to LOW) via user button triple press + +// RAK12002 RTC Module +#define RV3028_RTC (uint8_t)0b1010010 + +// RAK18001 Buzzer in Slot C +// #define PIN_BUZZER 21 // IO3 is PWM2 +// NEW: set this via protobuf instead! + +// Battery +// The battery sense is hooked to pin A0 (5) +#define BATTERY_PIN PIN_A0 +// and has 12 bit resolution +#define BATTERY_SENSE_RESOLUTION_BITS 12 +#define BATTERY_SENSE_RESOLUTION 4096.0 +#undef AREF_VOLTAGE +#define AREF_VOLTAGE 3.0 +#define VBAT_AR_INTERNAL AR_INTERNAL_3_0 +#define ADC_MULTIPLIER 1.73 + +#define HAS_RTC 1 + +#define HAS_ETHERNET 1 + +#define RAK_4631 1 + +#define PIN_ETHERNET_RESET 21 +#define PIN_ETHERNET_SS PIN_EINK_CS +#define ETH_SPI_PORT SPI1 +#define AQ_SET_PIN 10 + +#ifdef __cplusplus +} +#endif + +/*---------------------------------------------------------------------------- + * Arduino objects - C++ only + *----------------------------------------------------------------------------*/ + +#endif \ No newline at end of file From c6bffd7d7f27f84f44559b6d5b4df40e08eac70a Mon Sep 17 00:00:00 2001 From: Bernd Giesecke Date: Mon, 9 Sep 2024 12:39:14 +0800 Subject: [PATCH 02/88] Update platformio.ini Fix default build environment --- platformio.ini | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/platformio.ini b/platformio.ini index a39de33c1..c10128609 100644 --- a/platformio.ini +++ b/platformio.ini @@ -2,7 +2,7 @@ ; https://docs.platformio.org/page/projectconf.html [platformio] -;default_envs = tbeam +default_envs = tbeam ;default_envs = pico ;default_envs = tbeam-s3-core ;default_envs = tbeam0.7 @@ -29,7 +29,7 @@ ;default_envs = meshtastic-dr-dev ;default_envs = m5stack-coreink ;default_envs = rak4631 -default_envs = rak4631_mqtt_json +;default_envs = rak4631_mqtt_json ;default_envs = rak2560 ;default_envs = rak10701 ;default_envs = wio-e5 @@ -161,4 +161,4 @@ lib_deps = mprograms/QMC5883LCompass@^1.2.0 - https://github.com/meshtastic/DFRobot_LarkWeatherStation#dee914270dc7cb3e43fbf034edd85a63a16a12ee \ No newline at end of file + https://github.com/meshtastic/DFRobot_LarkWeatherStation#dee914270dc7cb3e43fbf034edd85a63a16a12ee From d02ba45109beea43a2a49c878ac99d356b9e92ee Mon Sep 17 00:00:00 2001 From: beegee-tokyo Date: Mon, 9 Sep 2024 12:40:56 +0800 Subject: [PATCH 03/88] Fix default build platform --- platformio.ini | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/platformio.ini b/platformio.ini index a39de33c1..552e026aa 100644 --- a/platformio.ini +++ b/platformio.ini @@ -2,7 +2,7 @@ ; https://docs.platformio.org/page/projectconf.html [platformio] -;default_envs = tbeam +default_envs = tbeam ;default_envs = pico ;default_envs = tbeam-s3-core ;default_envs = tbeam0.7 @@ -29,7 +29,7 @@ ;default_envs = meshtastic-dr-dev ;default_envs = m5stack-coreink ;default_envs = rak4631 -default_envs = rak4631_mqtt_json +;default_envs = rak4631_mqtt_json ;default_envs = rak2560 ;default_envs = rak10701 ;default_envs = wio-e5 From 91887865818bda76ea62a12c00ee3096a5380981 Mon Sep 17 00:00:00 2001 From: beegee-tokyo Date: Tue, 10 Sep 2024 11:58:25 +0800 Subject: [PATCH 04/88] Fix #ifndef and rename the variant --- platformio.ini | 2 +- src/mqtt/MQTT.cpp | 12 +++++----- .../platformio.ini | 24 ++++++++++++------- .../variant.cpp | 0 .../variant.h | 0 5 files changed, 23 insertions(+), 15 deletions(-) rename variants/{rak4631_mqtt_json => rak4631_eth_gw}/platformio.ini (80%) rename variants/{rak4631_mqtt_json => rak4631_eth_gw}/variant.cpp (100%) rename variants/{rak4631_mqtt_json => rak4631_eth_gw}/variant.h (100%) diff --git a/platformio.ini b/platformio.ini index c10128609..f47b801ce 100644 --- a/platformio.ini +++ b/platformio.ini @@ -29,7 +29,7 @@ default_envs = tbeam ;default_envs = meshtastic-dr-dev ;default_envs = m5stack-coreink ;default_envs = rak4631 -;default_envs = rak4631_mqtt_json +;default_envs = rak4631_eth_gw ;default_envs = rak2560 ;default_envs = rak10701 ;default_envs = wio-e5 diff --git a/src/mqtt/MQTT.cpp b/src/mqtt/MQTT.cpp index 63bdd5bba..33a22e5d4 100644 --- a/src/mqtt/MQTT.cpp +++ b/src/mqtt/MQTT.cpp @@ -379,13 +379,13 @@ void MQTT::sendSubscriptions() std::string topic = cryptTopic + channels.getGlobalId(i) + "/+"; LOG_INFO("Subscribing to %s\n", topic.c_str()); pubSub.subscribe(topic.c_str(), 1); // FIXME, is QOS 1 right? -// #ifndef ARCH_NRF52 // JSON is not supported on nRF52, see issue #2804 ### Fixed by using ArduinoJSON ### +#if !defined(ARCH_NRF52) || defined(NRF52_USE_JSON) // JSON is not supported on nRF52, see issue #2804 ### Fixed by using ArduinoJSON ### if (moduleConfig.mqtt.json_enabled == true) { std::string topicDecoded = jsonTopic + channels.getGlobalId(i) + "/+"; LOG_INFO("Subscribing to %s\n", topicDecoded.c_str()); pubSub.subscribe(topicDecoded.c_str(), 1); // FIXME, is QOS 1 right? } -// #endif // ARCH_NRF52 +#endif // ARCH_NRF52 NRF52_USE_JSON } } #if !MESHTASTIC_EXCLUDE_PKI @@ -480,7 +480,7 @@ void MQTT::publishQueuedMessages() publish(topic.c_str(), bytes, numBytes, false); -// #ifndef ARCH_NRF52 // JSON is not supported on nRF52, see issue #2804 ### Fixed by using ArduinoJson ### +#if !defined(ARCH_NRF52) || defined(NRF52_USE_JSON) // JSON is not supported on nRF52, see issue #2804 ### Fixed by using ArduinoJson ### if (moduleConfig.mqtt.json_enabled) { // handle json topic auto jsonString = MeshPacketSerializer::JsonSerialize(env->packet); @@ -496,7 +496,7 @@ void MQTT::publishQueuedMessages() publish(topicJson.c_str(), jsonString.c_str(), false); } } -// #endif // ARCH_NRF52 +#endif // ARCH_NRF52 NRF52_USE_JSON mqttPool.release(env); } } @@ -562,7 +562,7 @@ void MQTT::onSend(const meshtastic_MeshPacket &mp, const meshtastic_MeshPacket & publish(topic.c_str(), bytes, numBytes, false); -// #ifndef ARCH_NRF52 // JSON is not supported on nRF52, see issue #2804 ### Fixed by using ArduinoJson ### +#if !defined(ARCH_NRF52) || defined(NRF52_USE_JSON) // JSON is not supported on nRF52, see issue #2804 ### Fixed by using ArduinoJson ### if (moduleConfig.mqtt.json_enabled) { // handle json topic auto jsonString = MeshPacketSerializer::JsonSerialize((meshtastic_MeshPacket *)&mp_decoded); @@ -573,7 +573,7 @@ void MQTT::onSend(const meshtastic_MeshPacket &mp, const meshtastic_MeshPacket & publish(topicJson.c_str(), jsonString.c_str(), false); } } -// #endif // ARCH_NRF52 +#endif // ARCH_NRF52 NRF52_USE_JSON } else { LOG_INFO("MQTT not connected, queueing packet\n"); if (mqttQueue.numFree() == 0) { diff --git a/variants/rak4631_mqtt_json/platformio.ini b/variants/rak4631_eth_gw/platformio.ini similarity index 80% rename from variants/rak4631_mqtt_json/platformio.ini rename to variants/rak4631_eth_gw/platformio.ini index 5d459a91a..bf8713293 100644 --- a/variants/rak4631_mqtt_json/platformio.ini +++ b/variants/rak4631_eth_gw/platformio.ini @@ -1,21 +1,29 @@ ; The very slick RAK wireless RAK 4631 / 4630 board - Unified firmware for 5005/19003, with or without OLED RAK 1921 -[env:rak4631_mqtt_json] +[env:rak4631_eth_gw] extends = nrf52840_base board = wiscore_rak4631 board_check = true -build_flags = ${nrf52840_base.build_flags} -Ivariants/rak4631_mqtt_json -D RAK_4631 +build_flags = ${nrf52840_base.build_flags} -Ivariants/rak4631_eth_gw -D RAK_4631 -L "${platformio.libdeps_dir}/${this.__env__}/bsec2/src/cortex-m4/fpv4-sp-d16-hard" -DGPS_POWER_TOGGLE ; comment this line to disable triple press function on the user button to turn off gps entirely. -DEINK_DISPLAY_MODEL=GxEPD2_213_BN -DEINK_WIDTH=250 -DEINK_HEIGHT=122 -DNRF52_USE_JSON=1 -; -DMESHTASTIC_EXCLUDE_GPS=1 + -DMESHTASTIC_EXCLUDE_GPS=1 -DMESHTASTIC_EXCLUDE_WIFI=1 ; -DMESHTASTIC_EXCLUDE_SCREEN=1 - -DMESHTASTIC_EXCLUDE_PKI=1 +; -DMESHTASTIC_EXCLUDE_PKI=1 -DMESHTASTIC_EXCLUDE_POWER_FSM=1 -build_src_filter = ${nrf52_base.build_src_filter} +<../variants/rak4631_mqtt_json> + + + + -DMESHTASTIC_EXCLUDE_POWERMON=1 + -DMESHTASTIC_EXCLUDE_TZ=1 + -DMESHTASTIC_EXCLUDE_EXTERNALNOTIFICATION=1 + -DMESHTASTIC_EXCLUDE_PAXCOUNTER=1 + -DMESHTASTIC_EXCLUDE_REMOTEHARDWARE=1 + -DMESHTASTIC_EXCLUDE_STOREFORWARD=1 + -DMESHTASTIC_EXCLUDE_CANNEDMESSAGES=1 + -DMESHTASTIC_EXCLUDE_WAYPOINT=1 +build_src_filter = ${nrf52_base.build_src_filter} +<../variants/rak4631_eth_gw> + + + lib_deps = ${nrf52840_base.lib_deps} ${networking_base.lib_deps} @@ -31,7 +39,7 @@ lib_deps = ; Allows programming and debug via the RAK NanoDAP as the default debugger tool for the RAK4631 (it is only $10!) ; programming time is about the same as the bootloader version. ; For information on this see the meshtastic developers documentation for "Development on the NRF52" -[env:rak4631_mqtt_json_dbg] +[env:rak4631_eth_gw_dbg] extends = env:rak4631 board_level = extra @@ -39,11 +47,11 @@ board_level = extra ; platform_packages = platformio/tool-openocd@^3.1200.0 build_flags = - ${env:rak4631_mqtt_json.build_flags} + ${env:rak4631_eth_gw.build_flags} -D USE_SEMIHOSTING lib_deps = - ${env:rak4631_mqtt_json.lib_deps} + ${env:rak4631_eth_gw.lib_deps} https://github.com/geeksville/Armduino-Semihosting.git#35b538fdf208c3530c1434cd099a08e486672ee4 ; NOTE: the pyocd support for semihosting is buggy. So I switched to using the builtin platformio support for the stlink adapter which worked much better. diff --git a/variants/rak4631_mqtt_json/variant.cpp b/variants/rak4631_eth_gw/variant.cpp similarity index 100% rename from variants/rak4631_mqtt_json/variant.cpp rename to variants/rak4631_eth_gw/variant.cpp diff --git a/variants/rak4631_mqtt_json/variant.h b/variants/rak4631_eth_gw/variant.h similarity index 100% rename from variants/rak4631_mqtt_json/variant.h rename to variants/rak4631_eth_gw/variant.h From 4fc3782ea3133f6bd097053687456d00725dd512 Mon Sep 17 00:00:00 2001 From: beegee-tokyo Date: Tue, 10 Sep 2024 18:43:47 +0800 Subject: [PATCH 05/88] Fix traceroute, neighborinfo and waypoint --- .../MeshPacketSerializer_nRF52.cpp | 55 ++++++++++++++----- 1 file changed, 41 insertions(+), 14 deletions(-) diff --git a/src/serialization/MeshPacketSerializer_nRF52.cpp b/src/serialization/MeshPacketSerializer_nRF52.cpp index 7302e0915..777c10ada 100644 --- a/src/serialization/MeshPacketSerializer_nRF52.cpp +++ b/src/serialization/MeshPacketSerializer_nRF52.cpp @@ -11,19 +11,18 @@ #include #include "mesh/generated/meshtastic/remote_hardware.pb.h" -StaticJsonDocument<512> jsonObj; -// StaticJsonDocument<512> msgPayload; +StaticJsonDocument<1024> jsonObj; +StaticJsonDocument<1024> arrayObj; std::string MeshPacketSerializer::JsonSerialize(const meshtastic_MeshPacket *mp, bool shouldLog) { // the created jsonObj is immutable after creation, so // we need to do the heavy lifting before assembling it. std::string msgType; - // JSONObject jsonObj; jsonObj.clear(); + arrayObj.clear(); if (mp->which_payload_variant == meshtastic_MeshPacket_decoded_tag) { - // JSONObject msgPayload; switch (mp->decoded.portnum) { case meshtastic_PortNum_TEXT_MESSAGE_APP: { msgType = "text"; @@ -43,7 +42,6 @@ std::string MeshPacketSerializer::JsonSerialize(const meshtastic_MeshPacket *mp, if (shouldLog) LOG_INFO("text message payload is of type plaintext\n"); jsonObj["payload"]["text"] = payloadStr; - // jsonObj["payload"] = msgPayload; } else { // if it is, then we can just use the json object if (shouldLog) @@ -96,6 +94,7 @@ std::string MeshPacketSerializer::JsonSerialize(const meshtastic_MeshPacket *mp, } } else if (shouldLog) { LOG_ERROR("Error decoding protobuf for telemetry message!\n"); + return ""; } break; } @@ -113,6 +112,7 @@ std::string MeshPacketSerializer::JsonSerialize(const meshtastic_MeshPacket *mp, jsonObj["payload"]["role"] = (int)decoded->role; } else if (shouldLog) { LOG_ERROR("Error decoding protobuf for nodeinfo message!\n"); + return ""; } break; } @@ -157,6 +157,7 @@ std::string MeshPacketSerializer::JsonSerialize(const meshtastic_MeshPacket *mp, } } else if (shouldLog) { LOG_ERROR("Error decoding protobuf for position message!\n"); + return ""; } break; } @@ -176,6 +177,7 @@ std::string MeshPacketSerializer::JsonSerialize(const meshtastic_MeshPacket *mp, jsonObj["payload"]["longitude_i"] = (int)decoded->longitude_i; } else if (shouldLog) { LOG_ERROR("Error decoding protobuf for position message!\n"); + return ""; } break; } @@ -192,16 +194,21 @@ std::string MeshPacketSerializer::JsonSerialize(const meshtastic_MeshPacket *mp, jsonObj["payload"]["last_sent_by_id"] = (unsigned int)decoded->last_sent_by_id; jsonObj["payload"]["neighbors_count"] = decoded->neighbors_count; - JsonArray neighbors = jsonObj.createNestedArray("neighbors"); + JsonObject neighbors_obj = arrayObj.to(); + JsonArray neighbors = neighbors_obj.createNestedArray("neighbors"); JsonObject neighbors_0 = neighbors.createNestedObject(); for (uint8_t i = 0; i < decoded->neighbors_count; i++) { neighbors_0["node_id"] = (unsigned int)decoded->neighbors[i].node_id; neighbors_0["snr"] = (int)decoded->neighbors[i].snr; + neighbors[i+1] = neighbors_0; neighbors_0.clear(); } + neighbors.remove(0); + jsonObj["payload"]["neighbors"] = neighbors; } else if (shouldLog) { LOG_ERROR("Error decoding protobuf for neighborinfo message!\n"); + return ""; } break; } @@ -214,17 +221,32 @@ std::string MeshPacketSerializer::JsonSerialize(const meshtastic_MeshPacket *mp, if (pb_decode_from_bytes(mp->decoded.payload.bytes, mp->decoded.payload.size, &meshtastic_RouteDiscovery_msg, &scratch)) { decoded = &scratch; - JsonArray route = jsonObj.createNestedArray("route"); + JsonArray route = arrayObj.createNestedArray("route"); - route.add(mp->to); + auto addToRoute = [](JsonArray *route, NodeNum num) { + char long_name[40] = "Unknown"; + meshtastic_NodeInfoLite *node = nodeDB->getMeshNode(num); + bool name_known = node ? node->has_user : false; + if (name_known) + memcpy(long_name, node->user.long_name, sizeof(long_name)); + route->add(long_name); + }; + + addToRoute(&route,mp->to); //route.add(mp->to); for (uint8_t i = 0; i < decoded->route_count; i++) { - route.add(decoded->route[i]); + addToRoute(&route,decoded->route[i]); //route.add(decoded->route[i]); } - route.add(mp->from); // Ended at the original destination (source of response) + addToRoute(&route,mp->from); //route.add(mp->from); // Ended at the original destination (source of response) + + jsonObj["payload"]["route"] = route; } else if (shouldLog) { LOG_ERROR("Error decoding protobuf for traceroute message!\n"); + return ""; } - } + } else { + LOG_WARN("Traceroute response not reported"); + return ""; + } break; } case meshtastic_PortNum_DETECTION_SENSOR_APP: { @@ -252,15 +274,19 @@ std::string MeshPacketSerializer::JsonSerialize(const meshtastic_MeshPacket *mp, } } else if (shouldLog) { LOG_ERROR("Error decoding protobuf for RemoteHardware message!\n"); + return ""; } break; } // add more packet types here if needed default: + LOG_WARN("Unsupported packet type %d\n",mp->decoded.portnum); + return ""; break; } } else if (shouldLog) { LOG_WARN("Couldn't convert encrypted payload of MeshPacket to JSON\n"); + return ""; } jsonObj["id"] = (unsigned int)mp->id; @@ -281,9 +307,9 @@ std::string MeshPacketSerializer::JsonSerialize(const meshtastic_MeshPacket *mp, // serialize and write it to the stream - Serial.printf("serialized json message: \r\n"); - serializeJson(jsonObj, Serial); - Serial.println(""); + // Serial.printf("serialized json message: \r\n"); + // serializeJson(jsonObj, Serial); + // Serial.println(""); std::string jsonStr = ""; serializeJson(jsonObj, jsonStr); @@ -296,6 +322,7 @@ std::string MeshPacketSerializer::JsonSerialize(const meshtastic_MeshPacket *mp, std::string MeshPacketSerializer::JsonSerializeEncrypted(const meshtastic_MeshPacket *mp) { + jsonObj.clear(); jsonObj["id"] = (unsigned int)mp->id; jsonObj["time_ms"] = (double)millis(); jsonObj["timestamp"] = (unsigned int)mp->rx_time; From 35cdc81d452dddf96edecb80609957756165d16f Mon Sep 17 00:00:00 2001 From: beegee-tokyo Date: Thu, 12 Sep 2024 09:53:13 +0800 Subject: [PATCH 06/88] Disable SCREEN and enable TZ --- src/AccelerometerThread.h | 16 +++++++++------- src/platform/nrf52/NRF52Bluetooth.cpp | 10 ++++++---- variants/rak4631_eth_gw/platformio.ini | 4 ++-- 3 files changed, 17 insertions(+), 13 deletions(-) diff --git a/src/AccelerometerThread.h b/src/AccelerometerThread.h index c2910007e..c39504c08 100644 --- a/src/AccelerometerThread.h +++ b/src/AccelerometerThread.h @@ -94,8 +94,9 @@ class AccelerometerThread : public concurrency::OSThread wakeScreen(); return 500; } -#ifdef RAK_4631 - } else if (acceleremoter_type == ScanI2C::DeviceType::BMX160) { +#if defined(RAK_4631) +#if !defined (MESHTASTIC_EXCLUDE_SCREEN) + } else if (acceleremoter_type == ScanI2C::DeviceType::BMX160) { sBmx160SensorData_t magAccel; sBmx160SensorData_t gAccel; @@ -165,7 +166,7 @@ class AccelerometerThread : public concurrency::OSThread } screen->setHeading(heading); - +#endif #endif } else if (acceleremoter_type == ScanI2C::DeviceType::LSM6DS3 && lsm.shake()) { wakeScreen(); @@ -230,9 +231,10 @@ class AccelerometerThread : public concurrency::OSThread // It corresponds to isDoubleClick interrupt bmaSensor.enableWakeupIRQ(); #ifdef RAK_4631 - } else if (acceleremoter_type == ScanI2C::DeviceType::BMX160 && bmx160.begin()) { +#if !defined(MESHTASTIC_EXCLUDE_SCREEN) + } else if (acceleremoter_type == ScanI2C::DeviceType::BMX160 && bmx160.begin()) { bmx160.ODR_Config(BMX160_ACCEL_ODR_100HZ, BMX160_GYRO_ODR_100HZ); // set output data rate - +#endif #endif } else if (acceleremoter_type == ScanI2C::DeviceType::LSM6DS3 && lsm.begin_I2C(accelerometer_found.address)) { LOG_DEBUG("LSM6DS3 initializing\n"); @@ -265,8 +267,8 @@ class AccelerometerThread : public concurrency::OSThread Adafruit_LSM6DS3TRC lsm; SensorBMA423 bmaSensor; bool BMA_IRQ = false; -#ifdef RAK_4631 - bool showingScreen = false; +#if defined(RAK_4631) && !defined(MESHTASTIC_EXCLUDE_SCREEN) + bool showingScreen = false; RAK_BMX160 bmx160; float highestX = 0, lowestX = 0, highestY = 0, lowestY = 0, highestZ = 0, lowestZ = 0; diff --git a/src/platform/nrf52/NRF52Bluetooth.cpp b/src/platform/nrf52/NRF52Bluetooth.cpp index 1405ea4f3..177255b2f 100644 --- a/src/platform/nrf52/NRF52Bluetooth.cpp +++ b/src/platform/nrf52/NRF52Bluetooth.cpp @@ -310,7 +310,9 @@ bool NRF52Bluetooth::onPairingPasskey(uint16_t conn_handle, uint8_t const passke { LOG_INFO("BLE pairing process started with passkey %.3s %.3s\n", passkey, passkey + 3); powerFSM.trigger(EVENT_BLUETOOTH_PAIR); - screen->startAlert([](OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y) -> void { +#if !defined(MESHTASTIC_EXCLUDE_SCREEN) + screen->startAlert([](OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y) -> void + { char btPIN[16] = "888888"; snprintf(btPIN, sizeof(btPIN), "%06u", configuredPasskey); int x_offset = display->width() / 2; @@ -333,9 +335,9 @@ bool NRF52Bluetooth::onPairingPasskey(uint16_t conn_handle, uint8_t const passke String deviceName = "Name: "; deviceName.concat(getDeviceName()); y_offset = display->height() == 64 ? y_offset + FONT_HEIGHT_LARGE - 6 : y_offset + FONT_HEIGHT_LARGE + 5; - display->drawString(x_offset + x, y_offset + y, deviceName); - }); - if (match_request) { + display->drawString(x_offset + x, y_offset + y, deviceName); }); +#endif + if (match_request) { uint32_t start_time = millis(); while (millis() < start_time + 30000) { if (!Bluefruit.connected(conn_handle)) diff --git a/variants/rak4631_eth_gw/platformio.ini b/variants/rak4631_eth_gw/platformio.ini index bf8713293..62b7e737d 100644 --- a/variants/rak4631_eth_gw/platformio.ini +++ b/variants/rak4631_eth_gw/platformio.ini @@ -12,11 +12,11 @@ build_flags = ${nrf52840_base.build_flags} -Ivariants/rak4631_eth_gw -D RAK_4631 -DNRF52_USE_JSON=1 -DMESHTASTIC_EXCLUDE_GPS=1 -DMESHTASTIC_EXCLUDE_WIFI=1 -; -DMESHTASTIC_EXCLUDE_SCREEN=1 + -DMESHTASTIC_EXCLUDE_SCREEN=1 ; -DMESHTASTIC_EXCLUDE_PKI=1 -DMESHTASTIC_EXCLUDE_POWER_FSM=1 -DMESHTASTIC_EXCLUDE_POWERMON=1 - -DMESHTASTIC_EXCLUDE_TZ=1 +; -DMESHTASTIC_EXCLUDE_TZ=1 -DMESHTASTIC_EXCLUDE_EXTERNALNOTIFICATION=1 -DMESHTASTIC_EXCLUDE_PAXCOUNTER=1 -DMESHTASTIC_EXCLUDE_REMOTEHARDWARE=1 From a388e78842c308427635281024c32016d4e2ccb5 Mon Sep 17 00:00:00 2001 From: beegee-tokyo Date: Thu, 12 Sep 2024 10:00:46 +0800 Subject: [PATCH 07/88] Fix platformio.ini conflict --- platformio.ini | 1 + 1 file changed, 1 insertion(+) diff --git a/platformio.ini b/platformio.ini index f47b801ce..1847bd113 100644 --- a/platformio.ini +++ b/platformio.ini @@ -162,3 +162,4 @@ lib_deps = https://github.com/meshtastic/DFRobot_LarkWeatherStation#dee914270dc7cb3e43fbf034edd85a63a16a12ee + https://github.com/gjelsoe/STK8xxx-Accelerometer.git#v0.1.1 \ No newline at end of file From ca8d2204ba4ed0cf147bf64fe4dcc4d0e4846cd4 Mon Sep 17 00:00:00 2001 From: beegee-tokyo Date: Thu, 12 Sep 2024 11:06:13 +0800 Subject: [PATCH 08/88] Fix formatting --- src/AccelerometerThread.h | 6 +- src/mqtt/MQTT.cpp | 1103 +++++++++-------- src/platform/nrf52/NRF52Bluetooth.cpp | 452 +++---- .../MeshPacketSerializer_nRF52.cpp | 647 +++++----- 4 files changed, 1194 insertions(+), 1014 deletions(-) diff --git a/src/AccelerometerThread.h b/src/AccelerometerThread.h index c39504c08..37e7aab0d 100644 --- a/src/AccelerometerThread.h +++ b/src/AccelerometerThread.h @@ -96,7 +96,7 @@ class AccelerometerThread : public concurrency::OSThread } #if defined(RAK_4631) #if !defined (MESHTASTIC_EXCLUDE_SCREEN) - } else if (acceleremoter_type == ScanI2C::DeviceType::BMX160) { + } else if (acceleremoter_type == ScanI2C::DeviceType::BMX160) { sBmx160SensorData_t magAccel; sBmx160SensorData_t gAccel; @@ -232,7 +232,7 @@ class AccelerometerThread : public concurrency::OSThread bmaSensor.enableWakeupIRQ(); #ifdef RAK_4631 #if !defined(MESHTASTIC_EXCLUDE_SCREEN) - } else if (acceleremoter_type == ScanI2C::DeviceType::BMX160 && bmx160.begin()) { + } else if (acceleremoter_type == ScanI2C::DeviceType::BMX160 && bmx160.begin()) { bmx160.ODR_Config(BMX160_ACCEL_ODR_100HZ, BMX160_GYRO_ODR_100HZ); // set output data rate #endif #endif @@ -268,7 +268,7 @@ class AccelerometerThread : public concurrency::OSThread SensorBMA423 bmaSensor; bool BMA_IRQ = false; #if defined(RAK_4631) && !defined(MESHTASTIC_EXCLUDE_SCREEN) - bool showingScreen = false; + bool showingScreen = false; RAK_BMX160 bmx160; float highestX = 0, lowestX = 0, highestY = 0, lowestY = 0, highestZ = 0, lowestZ = 0; diff --git a/src/mqtt/MQTT.cpp b/src/mqtt/MQTT.cpp index 33a22e5d4..3e0e692b4 100644 --- a/src/mqtt/MQTT.cpp +++ b/src/mqtt/MQTT.cpp @@ -33,161 +33,194 @@ Allocator &mqttPool = staticMqttPool; void MQTT::mqttCallback(char *topic, byte *payload, unsigned int length) { - mqtt->onReceive(topic, payload, length); + mqtt->onReceive(topic, payload, length); } void MQTT::onClientProxyReceive(meshtastic_MqttClientProxyMessage msg) { - onReceive(msg.topic, msg.payload_variant.data.bytes, msg.payload_variant.data.size); + onReceive(msg.topic, msg.payload_variant.data.bytes, msg.payload_variant.data.size); } void MQTT::onReceive(char *topic, byte *payload, size_t length) { - meshtastic_ServiceEnvelope e = meshtastic_ServiceEnvelope_init_default; + meshtastic_ServiceEnvelope e = meshtastic_ServiceEnvelope_init_default; - if (moduleConfig.mqtt.json_enabled && (strncmp(topic, jsonTopic.c_str(), jsonTopic.length()) == 0)) { - // check if this is a json payload message by comparing the topic start - char payloadStr[length + 1]; - memcpy(payloadStr, payload, length); - payloadStr[length] = 0; // null terminated string - JSONValue *json_value = JSON::Parse(payloadStr); - if (json_value != NULL) { - // check if it is a valid envelope - JSONObject json; - json = json_value->AsObject(); + if (moduleConfig.mqtt.json_enabled && (strncmp(topic, jsonTopic.c_str(), jsonTopic.length()) == 0)) + { + // check if this is a json payload message by comparing the topic start + char payloadStr[length + 1]; + memcpy(payloadStr, payload, length); + payloadStr[length] = 0; // null terminated string + JSONValue *json_value = JSON::Parse(payloadStr); + if (json_value != NULL) + { + // check if it is a valid envelope + JSONObject json; + json = json_value->AsObject(); - // parse the channel name from the topic string - // the topic has been checked above for having jsonTopic prefix, so just move past it - char *ptr = topic + jsonTopic.length(); - ptr = strtok(ptr, "/") ? strtok(ptr, "/") : ptr; // if another "/" was added, parse string up to that character - meshtastic_Channel sendChannel = channels.getByName(ptr); - // We allow downlink JSON packets only on a channel named "mqtt" - if (strncasecmp(channels.getGlobalId(sendChannel.index), Channels::mqttChannel, strlen(Channels::mqttChannel)) == 0 && - sendChannel.settings.downlink_enabled) { - if (isValidJsonEnvelope(json)) { - // this is a valid envelope - if (json["type"]->AsString().compare("sendtext") == 0 && json["payload"]->IsString()) { - std::string jsonPayloadStr = json["payload"]->AsString(); - LOG_INFO("JSON payload %s, length %u\n", jsonPayloadStr.c_str(), jsonPayloadStr.length()); + // parse the channel name from the topic string + // the topic has been checked above for having jsonTopic prefix, so just move past it + char *ptr = topic + jsonTopic.length(); + ptr = strtok(ptr, "/") ? strtok(ptr, "/") : ptr; // if another "/" was added, parse string up to that character + meshtastic_Channel sendChannel = channels.getByName(ptr); + // We allow downlink JSON packets only on a channel named "mqtt" + if (strncasecmp(channels.getGlobalId(sendChannel.index), Channels::mqttChannel, strlen(Channels::mqttChannel)) == 0 && + sendChannel.settings.downlink_enabled) + { + if (isValidJsonEnvelope(json)) + { + // this is a valid envelope + if (json["type"]->AsString().compare("sendtext") == 0 && json["payload"]->IsString()) + { + std::string jsonPayloadStr = json["payload"]->AsString(); + LOG_INFO("JSON payload %s, length %u\n", jsonPayloadStr.c_str(), jsonPayloadStr.length()); - // construct protobuf data packet using TEXT_MESSAGE, send it to the mesh - meshtastic_MeshPacket *p = router->allocForSending(); - p->decoded.portnum = meshtastic_PortNum_TEXT_MESSAGE_APP; - if (json.find("channel") != json.end() && json["channel"]->IsNumber() && - (json["channel"]->AsNumber() < channels.getNumChannels())) - p->channel = json["channel"]->AsNumber(); - if (json.find("to") != json.end() && json["to"]->IsNumber()) - p->to = json["to"]->AsNumber(); - if (json.find("hopLimit") != json.end() && json["hopLimit"]->IsNumber()) - p->hop_limit = json["hopLimit"]->AsNumber(); - if (jsonPayloadStr.length() <= sizeof(p->decoded.payload.bytes)) { - memcpy(p->decoded.payload.bytes, jsonPayloadStr.c_str(), jsonPayloadStr.length()); - p->decoded.payload.size = jsonPayloadStr.length(); - service->sendToMesh(p, RX_SRC_LOCAL); - } else { - LOG_WARN("Received MQTT json payload too long, dropping\n"); - } - } else if (json["type"]->AsString().compare("sendposition") == 0 && json["payload"]->IsObject()) { - // invent the "sendposition" type for a valid envelope - JSONObject posit; - posit = json["payload"]->AsObject(); // get nested JSON Position - meshtastic_Position pos = meshtastic_Position_init_default; - if (posit.find("latitude_i") != posit.end() && posit["latitude_i"]->IsNumber()) - pos.latitude_i = posit["latitude_i"]->AsNumber(); - if (posit.find("longitude_i") != posit.end() && posit["longitude_i"]->IsNumber()) - pos.longitude_i = posit["longitude_i"]->AsNumber(); - if (posit.find("altitude") != posit.end() && posit["altitude"]->IsNumber()) - pos.altitude = posit["altitude"]->AsNumber(); - if (posit.find("time") != posit.end() && posit["time"]->IsNumber()) - pos.time = posit["time"]->AsNumber(); + // construct protobuf data packet using TEXT_MESSAGE, send it to the mesh + meshtastic_MeshPacket *p = router->allocForSending(); + p->decoded.portnum = meshtastic_PortNum_TEXT_MESSAGE_APP; + if (json.find("channel") != json.end() && json["channel"]->IsNumber() && + (json["channel"]->AsNumber() < channels.getNumChannels())) + p->channel = json["channel"]->AsNumber(); + if (json.find("to") != json.end() && json["to"]->IsNumber()) + p->to = json["to"]->AsNumber(); + if (json.find("hopLimit") != json.end() && json["hopLimit"]->IsNumber()) + p->hop_limit = json["hopLimit"]->AsNumber(); + if (jsonPayloadStr.length() <= sizeof(p->decoded.payload.bytes)) + { + memcpy(p->decoded.payload.bytes, jsonPayloadStr.c_str(), jsonPayloadStr.length()); + p->decoded.payload.size = jsonPayloadStr.length(); + service->sendToMesh(p, RX_SRC_LOCAL); + } + else + { + LOG_WARN("Received MQTT json payload too long, dropping\n"); + } + } + else if (json["type"]->AsString().compare("sendposition") == 0 && json["payload"]->IsObject()) + { + // invent the "sendposition" type for a valid envelope + JSONObject posit; + posit = json["payload"]->AsObject(); // get nested JSON Position + meshtastic_Position pos = meshtastic_Position_init_default; + if (posit.find("latitude_i") != posit.end() && posit["latitude_i"]->IsNumber()) + pos.latitude_i = posit["latitude_i"]->AsNumber(); + if (posit.find("longitude_i") != posit.end() && posit["longitude_i"]->IsNumber()) + pos.longitude_i = posit["longitude_i"]->AsNumber(); + if (posit.find("altitude") != posit.end() && posit["altitude"]->IsNumber()) + pos.altitude = posit["altitude"]->AsNumber(); + if (posit.find("time") != posit.end() && posit["time"]->IsNumber()) + pos.time = posit["time"]->AsNumber(); - // construct protobuf data packet using POSITION, send it to the mesh - meshtastic_MeshPacket *p = router->allocForSending(); - p->decoded.portnum = meshtastic_PortNum_POSITION_APP; - if (json.find("channel") != json.end() && json["channel"]->IsNumber() && - (json["channel"]->AsNumber() < channels.getNumChannels())) - p->channel = json["channel"]->AsNumber(); - if (json.find("to") != json.end() && json["to"]->IsNumber()) - p->to = json["to"]->AsNumber(); - if (json.find("hopLimit") != json.end() && json["hopLimit"]->IsNumber()) - p->hop_limit = json["hopLimit"]->AsNumber(); - p->decoded.payload.size = - pb_encode_to_bytes(p->decoded.payload.bytes, sizeof(p->decoded.payload.bytes), - &meshtastic_Position_msg, &pos); // make the Data protobuf from position - service->sendToMesh(p, RX_SRC_LOCAL); - } else { - LOG_DEBUG("JSON Ignoring downlink message with unsupported type.\n"); - } - } else { - LOG_ERROR("JSON Received payload on MQTT but not a valid envelope.\n"); - } - } else { - LOG_WARN("JSON downlink received on channel not called 'mqtt' or without downlink enabled.\n"); - } - } else { - // no json, this is an invalid payload - LOG_ERROR("JSON Received payload on MQTT but not a valid JSON\n"); - } - delete json_value; - } else { - if (length == 0) { - LOG_WARN("Empty MQTT payload received, topic %s!\n", topic); - return; - } else if (!pb_decode_from_bytes(payload, length, &meshtastic_ServiceEnvelope_msg, &e)) { - LOG_ERROR("Invalid MQTT service envelope, topic %s, len %u!\n", topic, length); - return; - } else { - if (e.channel_id == NULL || e.gateway_id == NULL) { - LOG_ERROR("Invalid MQTT service envelope, topic %s, len %u!\n", topic, length); - return; - } - meshtastic_Channel ch = channels.getByName(e.channel_id); - if (strcmp(e.gateway_id, owner.id) == 0) { - // Generate an implicit ACK towards ourselves (handled and processed only locally!) for this message. - // We do this because packets are not rebroadcasted back into MQTT anymore and we assume that at least one node - // receives it when we get our own packet back. Then we'll stop our retransmissions. - if (e.packet && getFrom(e.packet) == nodeDB->getNodeNum()) - routingModule->sendAckNak(meshtastic_Routing_Error_NONE, getFrom(e.packet), e.packet->id, ch.index); - else - LOG_INFO("Ignoring downlink message we originally sent.\n"); - } else { - // Find channel by channel_id and check downlink_enabled - if ((strcmp(e.channel_id, "PKI") == 0 && e.packet) || - (strcmp(e.channel_id, channels.getGlobalId(ch.index)) == 0 && e.packet && ch.settings.downlink_enabled)) { - LOG_INFO("Received MQTT topic %s, len=%u\n", topic, length); - meshtastic_MeshPacket *p = packetPool.allocCopy(*e.packet); - p->via_mqtt = true; // Mark that the packet was received via MQTT + // construct protobuf data packet using POSITION, send it to the mesh + meshtastic_MeshPacket *p = router->allocForSending(); + p->decoded.portnum = meshtastic_PortNum_POSITION_APP; + if (json.find("channel") != json.end() && json["channel"]->IsNumber() && + (json["channel"]->AsNumber() < channels.getNumChannels())) + p->channel = json["channel"]->AsNumber(); + if (json.find("to") != json.end() && json["to"]->IsNumber()) + p->to = json["to"]->AsNumber(); + if (json.find("hopLimit") != json.end() && json["hopLimit"]->IsNumber()) + p->hop_limit = json["hopLimit"]->AsNumber(); + p->decoded.payload.size = + pb_encode_to_bytes(p->decoded.payload.bytes, sizeof(p->decoded.payload.bytes), + &meshtastic_Position_msg, &pos); // make the Data protobuf from position + service->sendToMesh(p, RX_SRC_LOCAL); + } + else + { + LOG_DEBUG("JSON Ignoring downlink message with unsupported type.\n"); + } + } + else + { + LOG_ERROR("JSON Received payload on MQTT but not a valid envelope.\n"); + } + } + else + { + LOG_WARN("JSON downlink received on channel not called 'mqtt' or without downlink enabled.\n"); + } + } + else + { + // no json, this is an invalid payload + LOG_ERROR("JSON Received payload on MQTT but not a valid JSON\n"); + } + delete json_value; + } + else + { + if (length == 0) + { + LOG_WARN("Empty MQTT payload received, topic %s!\n", topic); + return; + } + else if (!pb_decode_from_bytes(payload, length, &meshtastic_ServiceEnvelope_msg, &e)) + { + LOG_ERROR("Invalid MQTT service envelope, topic %s, len %u!\n", topic, length); + return; + } + else + { + if (e.channel_id == NULL || e.gateway_id == NULL) + { + LOG_ERROR("Invalid MQTT service envelope, topic %s, len %u!\n", topic, length); + return; + } + meshtastic_Channel ch = channels.getByName(e.channel_id); + if (strcmp(e.gateway_id, owner.id) == 0) + { + // Generate an implicit ACK towards ourselves (handled and processed only locally!) for this message. + // We do this because packets are not rebroadcasted back into MQTT anymore and we assume that at least one node + // receives it when we get our own packet back. Then we'll stop our retransmissions. + if (e.packet && getFrom(e.packet) == nodeDB->getNodeNum()) + routingModule->sendAckNak(meshtastic_Routing_Error_NONE, getFrom(e.packet), e.packet->id, ch.index); + else + LOG_INFO("Ignoring downlink message we originally sent.\n"); + } + else + { + // Find channel by channel_id and check downlink_enabled + if ((strcmp(e.channel_id, "PKI") == 0 && e.packet) || + (strcmp(e.channel_id, channels.getGlobalId(ch.index)) == 0 && e.packet && ch.settings.downlink_enabled)) + { + LOG_INFO("Received MQTT topic %s, len=%u\n", topic, length); + meshtastic_MeshPacket *p = packetPool.allocCopy(*e.packet); + p->via_mqtt = true; // Mark that the packet was received via MQTT - if (p->which_payload_variant == meshtastic_MeshPacket_decoded_tag) { - p->channel = ch.index; - } + if (p->which_payload_variant == meshtastic_MeshPacket_decoded_tag) + { + p->channel = ch.index; + } - // PKI messages get accepted even if we can't decrypt - if (router && p->which_payload_variant == meshtastic_MeshPacket_encrypted_tag && - strcmp(e.channel_id, "PKI") == 0) { - meshtastic_NodeInfoLite *tx = nodeDB->getMeshNode(getFrom(p)); - meshtastic_NodeInfoLite *rx = nodeDB->getMeshNode(p->to); - // Only accept PKI messages to us, or if we have both the sender and receiver in our nodeDB, as then it's - // likely they discovered each other via a channel we have downlink enabled for - if (p->to == nodeDB->getNodeNum() || (tx && tx->has_user && rx && rx->has_user)) - router->enqueueReceivedMessage(p); - } else if (router && perhapsDecode(p)) // ignore messages if we don't have the channel key - router->enqueueReceivedMessage(p); - else - packetPool.release(p); - } - } - } - // make sure to free both strings and the MeshPacket (passing in NULL is acceptable) - free(e.channel_id); - free(e.gateway_id); - free(e.packet); - } + // PKI messages get accepted even if we can't decrypt + if (router && p->which_payload_variant == meshtastic_MeshPacket_encrypted_tag && + strcmp(e.channel_id, "PKI") == 0) + { + meshtastic_NodeInfoLite *tx = nodeDB->getMeshNode(getFrom(p)); + meshtastic_NodeInfoLite *rx = nodeDB->getMeshNode(p->to); + // Only accept PKI messages to us, or if we have both the sender and receiver in our nodeDB, as then it's + // likely they discovered each other via a channel we have downlink enabled for + if (p->to == nodeDB->getNodeNum() || (tx && tx->has_user && rx && rx->has_user)) + router->enqueueReceivedMessage(p); + } + else if (router && perhapsDecode(p)) // ignore messages if we don't have the channel key + router->enqueueReceivedMessage(p); + else + packetPool.release(p); + } + } + } + // make sure to free both strings and the MeshPacket (passing in NULL is acceptable) + free(e.channel_id); + free(e.gateway_id); + free(e.packet); + } } void mqttInit() { - new MQTT(); + new MQTT(); } #if HAS_NETWORKING @@ -196,483 +229,551 @@ MQTT::MQTT() : concurrency::OSThread("mqtt"), pubSub(mqttClient), mqttQueue(MAX_ MQTT::MQTT() : concurrency::OSThread("mqtt"), mqttQueue(MAX_MQTT_QUEUE) #endif { - if (moduleConfig.mqtt.enabled) { - LOG_DEBUG("Initializing MQTT\n"); + if (moduleConfig.mqtt.enabled) + { + LOG_DEBUG("Initializing MQTT\n"); - assert(!mqtt); - mqtt = this; + assert(!mqtt); + mqtt = this; - if (*moduleConfig.mqtt.root) { - cryptTopic = moduleConfig.mqtt.root + cryptTopic; - jsonTopic = moduleConfig.mqtt.root + jsonTopic; - mapTopic = moduleConfig.mqtt.root + mapTopic; - } else { - cryptTopic = "msh" + cryptTopic; - jsonTopic = "msh" + jsonTopic; - mapTopic = "msh" + mapTopic; - } + if (*moduleConfig.mqtt.root) + { + cryptTopic = moduleConfig.mqtt.root + cryptTopic; + jsonTopic = moduleConfig.mqtt.root + jsonTopic; + mapTopic = moduleConfig.mqtt.root + mapTopic; + } + else + { + cryptTopic = "msh" + cryptTopic; + jsonTopic = "msh" + jsonTopic; + mapTopic = "msh" + mapTopic; + } - if (moduleConfig.mqtt.map_reporting_enabled && moduleConfig.mqtt.has_map_report_settings) { - map_position_precision = Default::getConfiguredOrDefault(moduleConfig.mqtt.map_report_settings.position_precision, - default_map_position_precision); - map_publish_interval_msecs = Default::getConfiguredOrDefaultMs( - moduleConfig.mqtt.map_report_settings.publish_interval_secs, default_map_publish_interval_secs); - } + if (moduleConfig.mqtt.map_reporting_enabled && moduleConfig.mqtt.has_map_report_settings) + { + map_position_precision = Default::getConfiguredOrDefault(moduleConfig.mqtt.map_report_settings.position_precision, + default_map_position_precision); + map_publish_interval_msecs = Default::getConfiguredOrDefaultMs( + moduleConfig.mqtt.map_report_settings.publish_interval_secs, default_map_publish_interval_secs); + } #if HAS_NETWORKING - if (!moduleConfig.mqtt.proxy_to_client_enabled) - pubSub.setCallback(mqttCallback); + if (!moduleConfig.mqtt.proxy_to_client_enabled) + pubSub.setCallback(mqttCallback); #endif - if (moduleConfig.mqtt.proxy_to_client_enabled) { - LOG_INFO("MQTT configured to use client proxy...\n"); - enabled = true; - runASAP = true; - reconnectCount = 0; - publishNodeInfo(); - } - // preflightSleepObserver.observe(&preflightSleep); - } else { - disable(); - } + if (moduleConfig.mqtt.proxy_to_client_enabled) + { + LOG_INFO("MQTT configured to use client proxy...\n"); + enabled = true; + runASAP = true; + reconnectCount = 0; + publishNodeInfo(); + } + // preflightSleepObserver.observe(&preflightSleep); + } + else + { + disable(); + } } bool MQTT::isConnectedDirectly() { #if HAS_NETWORKING - return pubSub.connected(); + return pubSub.connected(); #else - return false; + return false; #endif } bool MQTT::publish(const char *topic, const char *payload, bool retained) { - if (moduleConfig.mqtt.proxy_to_client_enabled) { - meshtastic_MqttClientProxyMessage *msg = mqttClientProxyMessagePool.allocZeroed(); - msg->which_payload_variant = meshtastic_MqttClientProxyMessage_text_tag; - strcpy(msg->topic, topic); - strcpy(msg->payload_variant.text, payload); - msg->retained = retained; - service->sendMqttMessageToClientProxy(msg); - return true; - } + if (moduleConfig.mqtt.proxy_to_client_enabled) + { + meshtastic_MqttClientProxyMessage *msg = mqttClientProxyMessagePool.allocZeroed(); + msg->which_payload_variant = meshtastic_MqttClientProxyMessage_text_tag; + strcpy(msg->topic, topic); + strcpy(msg->payload_variant.text, payload); + msg->retained = retained; + service->sendMqttMessageToClientProxy(msg); + return true; + } #if HAS_NETWORKING - else if (isConnectedDirectly()) { - return pubSub.publish(topic, payload, retained); - } + else if (isConnectedDirectly()) + { + return pubSub.publish(topic, payload, retained); + } #endif - return false; + return false; } bool MQTT::publish(const char *topic, const uint8_t *payload, size_t length, bool retained) { - if (moduleConfig.mqtt.proxy_to_client_enabled) { - meshtastic_MqttClientProxyMessage *msg = mqttClientProxyMessagePool.allocZeroed(); - msg->which_payload_variant = meshtastic_MqttClientProxyMessage_data_tag; - strcpy(msg->topic, topic); - msg->payload_variant.data.size = length; - memcpy(msg->payload_variant.data.bytes, payload, length); - msg->retained = retained; - service->sendMqttMessageToClientProxy(msg); - return true; - } + if (moduleConfig.mqtt.proxy_to_client_enabled) + { + meshtastic_MqttClientProxyMessage *msg = mqttClientProxyMessagePool.allocZeroed(); + msg->which_payload_variant = meshtastic_MqttClientProxyMessage_data_tag; + strcpy(msg->topic, topic); + msg->payload_variant.data.size = length; + memcpy(msg->payload_variant.data.bytes, payload, length); + msg->retained = retained; + service->sendMqttMessageToClientProxy(msg); + return true; + } #if HAS_NETWORKING - else if (isConnectedDirectly()) { - return pubSub.publish(topic, payload, length, retained); - } + else if (isConnectedDirectly()) + { + return pubSub.publish(topic, payload, length, retained); + } #endif - return false; + return false; } void MQTT::reconnect() { - if (wantsLink()) { - if (moduleConfig.mqtt.proxy_to_client_enabled) { - LOG_INFO("MQTT connecting via client proxy instead...\n"); - enabled = true; - runASAP = true; - reconnectCount = 0; + if (wantsLink()) + { + if (moduleConfig.mqtt.proxy_to_client_enabled) + { + LOG_INFO("MQTT connecting via client proxy instead...\n"); + enabled = true; + runASAP = true; + reconnectCount = 0; - publishNodeInfo(); - return; // Don't try to connect directly to the server - } + publishNodeInfo(); + return; // Don't try to connect directly to the server + } #if HAS_NETWORKING - // Defaults - int serverPort = 1883; - const char *serverAddr = default_mqtt_address; - const char *mqttUsername = default_mqtt_username; - const char *mqttPassword = default_mqtt_password; + // Defaults + int serverPort = 1883; + const char *serverAddr = default_mqtt_address; + const char *mqttUsername = default_mqtt_username; + const char *mqttPassword = default_mqtt_password; - if (*moduleConfig.mqtt.address) { - serverAddr = moduleConfig.mqtt.address; - mqttUsername = moduleConfig.mqtt.username; - mqttPassword = moduleConfig.mqtt.password; - } + if (*moduleConfig.mqtt.address) + { + serverAddr = moduleConfig.mqtt.address; + mqttUsername = moduleConfig.mqtt.username; + mqttPassword = moduleConfig.mqtt.password; + } #if HAS_WIFI && !defined(ARCH_PORTDUINO) - if (moduleConfig.mqtt.tls_enabled) { - // change default for encrypted to 8883 - try { - serverPort = 8883; - wifiSecureClient.setInsecure(); + if (moduleConfig.mqtt.tls_enabled) + { + // change default for encrypted to 8883 + try + { + serverPort = 8883; + wifiSecureClient.setInsecure(); - pubSub.setClient(wifiSecureClient); - LOG_INFO("Using TLS-encrypted session\n"); - } catch (const std::exception &e) { - LOG_ERROR("MQTT ERROR: %s\n", e.what()); - } - } else { - LOG_INFO("Using non-TLS-encrypted session\n"); - pubSub.setClient(mqttClient); - } + pubSub.setClient(wifiSecureClient); + LOG_INFO("Using TLS-encrypted session\n"); + } + catch (const std::exception &e) + { + LOG_ERROR("MQTT ERROR: %s\n", e.what()); + } + } + else + { + LOG_INFO("Using non-TLS-encrypted session\n"); + pubSub.setClient(mqttClient); + } #elif HAS_NETWORKING - pubSub.setClient(mqttClient); + pubSub.setClient(mqttClient); #endif - String server = String(serverAddr); - int delimIndex = server.indexOf(':'); - if (delimIndex > 0) { - String port = server.substring(delimIndex + 1, server.length()); - server[delimIndex] = 0; - serverPort = port.toInt(); - serverAddr = server.c_str(); - } - pubSub.setServer(serverAddr, serverPort); - pubSub.setBufferSize(512); + String server = String(serverAddr); + int delimIndex = server.indexOf(':'); + if (delimIndex > 0) + { + String port = server.substring(delimIndex + 1, server.length()); + server[delimIndex] = 0; + serverPort = port.toInt(); + serverAddr = server.c_str(); + } + pubSub.setServer(serverAddr, serverPort); + pubSub.setBufferSize(512); - LOG_INFO("Attempting to connect directly to MQTT server %s, port: %d, username: %s, password: %s\n", serverAddr, - serverPort, mqttUsername, mqttPassword); + LOG_INFO("Attempting to connect directly to MQTT server %s, port: %d, username: %s, password: %s\n", serverAddr, + serverPort, mqttUsername, mqttPassword); - bool connected = pubSub.connect(owner.id, mqttUsername, mqttPassword); - if (connected) { - LOG_INFO("MQTT connected\n"); - enabled = true; // Start running background process again - runASAP = true; - reconnectCount = 0; + bool connected = pubSub.connect(owner.id, mqttUsername, mqttPassword); + if (connected) + { + LOG_INFO("MQTT connected\n"); + enabled = true; // Start running background process again + runASAP = true; + reconnectCount = 0; - publishNodeInfo(); - sendSubscriptions(); - } else { + publishNodeInfo(); + sendSubscriptions(); + } + else + { #if HAS_WIFI && !defined(ARCH_PORTDUINO) - reconnectCount++; - LOG_ERROR("Failed to contact MQTT server directly (%d/%d)...\n", reconnectCount, reconnectMax); - if (reconnectCount >= reconnectMax) { - needReconnect = true; - wifiReconnect->setIntervalFromNow(0); - reconnectCount = 0; - } + reconnectCount++; + LOG_ERROR("Failed to contact MQTT server directly (%d/%d)...\n", reconnectCount, reconnectMax); + if (reconnectCount >= reconnectMax) + { + needReconnect = true; + wifiReconnect->setIntervalFromNow(0); + reconnectCount = 0; + } #endif - } + } #endif - } + } } void MQTT::sendSubscriptions() { #if HAS_NETWORKING - bool hasDownlink = false; - size_t numChan = channels.getNumChannels(); - for (size_t i = 0; i < numChan; i++) { - const auto &ch = channels.getByIndex(i); - if (ch.settings.downlink_enabled) { - hasDownlink = true; - std::string topic = cryptTopic + channels.getGlobalId(i) + "/+"; - LOG_INFO("Subscribing to %s\n", topic.c_str()); - pubSub.subscribe(topic.c_str(), 1); // FIXME, is QOS 1 right? -#if !defined(ARCH_NRF52) || defined(NRF52_USE_JSON) // JSON is not supported on nRF52, see issue #2804 ### Fixed by using ArduinoJSON ### - if (moduleConfig.mqtt.json_enabled == true) { - std::string topicDecoded = jsonTopic + channels.getGlobalId(i) + "/+"; - LOG_INFO("Subscribing to %s\n", topicDecoded.c_str()); - pubSub.subscribe(topicDecoded.c_str(), 1); // FIXME, is QOS 1 right? - } + bool hasDownlink = false; + size_t numChan = channels.getNumChannels(); + for (size_t i = 0; i < numChan; i++) + { + const auto &ch = channels.getByIndex(i); + if (ch.settings.downlink_enabled) + { + hasDownlink = true; + std::string topic = cryptTopic + channels.getGlobalId(i) + "/+"; + LOG_INFO("Subscribing to %s\n", topic.c_str()); + pubSub.subscribe(topic.c_str(), 1); // FIXME, is QOS 1 right? +#if !defined(ARCH_NRF52) || defined(NRF52_USE_JSON) // JSON is not supported on nRF52, see issue #2804 ### Fixed by using ArduinoJSON ### + if (moduleConfig.mqtt.json_enabled == true) + { + std::string topicDecoded = jsonTopic + channels.getGlobalId(i) + "/+"; + LOG_INFO("Subscribing to %s\n", topicDecoded.c_str()); + pubSub.subscribe(topicDecoded.c_str(), 1); // FIXME, is QOS 1 right? + } #endif // ARCH_NRF52 NRF52_USE_JSON - } - } + } + } #if !MESHTASTIC_EXCLUDE_PKI - if (hasDownlink) { - std::string topic = cryptTopic + "PKI/+"; - LOG_INFO("Subscribing to %s\n", topic.c_str()); - pubSub.subscribe(topic.c_str(), 1); - } + if (hasDownlink) + { + std::string topic = cryptTopic + "PKI/+"; + LOG_INFO("Subscribing to %s\n", topic.c_str()); + pubSub.subscribe(topic.c_str(), 1); + } #endif #endif } bool MQTT::wantsLink() const { - bool hasChannelorMapReport = - moduleConfig.mqtt.enabled && (moduleConfig.mqtt.map_reporting_enabled || channels.anyMqttEnabled()); + bool hasChannelorMapReport = + moduleConfig.mqtt.enabled && (moduleConfig.mqtt.map_reporting_enabled || channels.anyMqttEnabled()); - if (hasChannelorMapReport && moduleConfig.mqtt.proxy_to_client_enabled) - return true; + if (hasChannelorMapReport && moduleConfig.mqtt.proxy_to_client_enabled) + return true; #if HAS_WIFI - return hasChannelorMapReport && WiFi.isConnected(); + return hasChannelorMapReport && WiFi.isConnected(); #endif #if HAS_ETHERNET - return hasChannelorMapReport && Ethernet.linkStatus() == LinkON; + return hasChannelorMapReport && Ethernet.linkStatus() == LinkON; #endif - return false; + return false; } int32_t MQTT::runOnce() { #if HAS_NETWORKING - if (!moduleConfig.mqtt.enabled || !(moduleConfig.mqtt.map_reporting_enabled || channels.anyMqttEnabled())) - return disable(); + if (!moduleConfig.mqtt.enabled || !(moduleConfig.mqtt.map_reporting_enabled || channels.anyMqttEnabled())) + return disable(); - bool wantConnection = wantsLink(); + bool wantConnection = wantsLink(); - perhapsReportToMap(); + perhapsReportToMap(); - // If connected poll rapidly, otherwise only occasionally check for a wifi connection change and ability to contact server - if (moduleConfig.mqtt.proxy_to_client_enabled) { - publishQueuedMessages(); - return 200; - } + // If connected poll rapidly, otherwise only occasionally check for a wifi connection change and ability to contact server + if (moduleConfig.mqtt.proxy_to_client_enabled) + { + publishQueuedMessages(); + return 200; + } + else if (!pubSub.loop()) + { + if (!wantConnection) + return 5000; // If we don't want connection now, check again in 5 secs + else + { + reconnect(); + // If we succeeded, empty the queue one by one and start reading rapidly, else try again in 30 seconds (TCP + // connections are EXPENSIVE so try rarely) + if (isConnectedDirectly()) + { + publishQueuedMessages(); + return 200; + } + else + return 30000; + } + } + else + { + // we are connected to server, check often for new requests on the TCP port + if (!wantConnection) + { + LOG_INFO("MQTT link not needed, dropping\n"); + pubSub.disconnect(); + } - else if (!pubSub.loop()) { - if (!wantConnection) - return 5000; // If we don't want connection now, check again in 5 secs - else { - reconnect(); - // If we succeeded, empty the queue one by one and start reading rapidly, else try again in 30 seconds (TCP - // connections are EXPENSIVE so try rarely) - if (isConnectedDirectly()) { - publishQueuedMessages(); - return 200; - } else - return 30000; - } - } else { - // we are connected to server, check often for new requests on the TCP port - if (!wantConnection) { - LOG_INFO("MQTT link not needed, dropping\n"); - pubSub.disconnect(); - } - - powerFSM.trigger(EVENT_CONTACT_FROM_PHONE); // Suppress entering light sleep (because that would turn off bluetooth) - return 20; - } + powerFSM.trigger(EVENT_CONTACT_FROM_PHONE); // Suppress entering light sleep (because that would turn off bluetooth) + return 20; + } #endif - return 30000; + return 30000; } void MQTT::publishNodeInfo() { - // TODO: NodeInfo broadcast over MQTT only (NODENUM_BROADCAST_NO_LORA) + // TODO: NodeInfo broadcast over MQTT only (NODENUM_BROADCAST_NO_LORA) } void MQTT::publishQueuedMessages() { - if (!mqttQueue.isEmpty()) { - LOG_DEBUG("Publishing enqueued MQTT message\n"); - // FIXME - this size calculation is super sloppy, but it will go away once we dynamically alloc meshpackets - meshtastic_ServiceEnvelope *env = mqttQueue.dequeuePtr(0); - static uint8_t bytes[meshtastic_MeshPacket_size + 64]; - size_t numBytes = pb_encode_to_bytes(bytes, sizeof(bytes), &meshtastic_ServiceEnvelope_msg, env); - std::string topic; - if (env->packet->pki_encrypted) { - topic = cryptTopic + "PKI/" + owner.id; - } else { - topic = cryptTopic + env->channel_id + "/" + owner.id; - } - LOG_INFO("publish %s, %u bytes from queue\n", topic.c_str(), numBytes); + if (!mqttQueue.isEmpty()) + { + LOG_DEBUG("Publishing enqueued MQTT message\n"); + // FIXME - this size calculation is super sloppy, but it will go away once we dynamically alloc meshpackets + meshtastic_ServiceEnvelope *env = mqttQueue.dequeuePtr(0); + static uint8_t bytes[meshtastic_MeshPacket_size + 64]; + size_t numBytes = pb_encode_to_bytes(bytes, sizeof(bytes), &meshtastic_ServiceEnvelope_msg, env); + std::string topic; + if (env->packet->pki_encrypted) + { + topic = cryptTopic + "PKI/" + owner.id; + } + else + { + topic = cryptTopic + env->channel_id + "/" + owner.id; + } + LOG_INFO("publish %s, %u bytes from queue\n", topic.c_str(), numBytes); - publish(topic.c_str(), bytes, numBytes, false); + publish(topic.c_str(), bytes, numBytes, false); -#if !defined(ARCH_NRF52) || defined(NRF52_USE_JSON) // JSON is not supported on nRF52, see issue #2804 ### Fixed by using ArduinoJson ### - if (moduleConfig.mqtt.json_enabled) { - // handle json topic - auto jsonString = MeshPacketSerializer::JsonSerialize(env->packet); - if (jsonString.length() != 0) { - std::string topicJson; - if (env->packet->pki_encrypted) { - topicJson = jsonTopic + "PKI/" + owner.id; - } else { - topicJson = jsonTopic + env->channel_id + "/" + owner.id; - } - LOG_INFO("JSON publish message to %s, %u bytes: %s\n", topicJson.c_str(), jsonString.length(), - jsonString.c_str()); - publish(topicJson.c_str(), jsonString.c_str(), false); - } - } +#if !defined(ARCH_NRF52) || defined(NRF52_USE_JSON) // JSON is not supported on nRF52, see issue #2804 ### Fixed by using ArduinoJson ### + if (moduleConfig.mqtt.json_enabled) + { + // handle json topic + auto jsonString = MeshPacketSerializer::JsonSerialize(env->packet); + if (jsonString.length() != 0) + { + std::string topicJson; + if (env->packet->pki_encrypted) + { + topicJson = jsonTopic + "PKI/" + owner.id; + } + else + { + topicJson = jsonTopic + env->channel_id + "/" + owner.id; + } + LOG_INFO("JSON publish message to %s, %u bytes: %s\n", topicJson.c_str(), jsonString.length(), + jsonString.c_str()); + publish(topicJson.c_str(), jsonString.c_str(), false); + } + } #endif // ARCH_NRF52 NRF52_USE_JSON - mqttPool.release(env); - } + mqttPool.release(env); + } } void MQTT::onSend(const meshtastic_MeshPacket &mp, const meshtastic_MeshPacket &mp_decoded, ChannelIndex chIndex) { - if (mp.via_mqtt) - return; // Don't send messages that came from MQTT back into MQTT - bool uplinkEnabled = false; - for (int i = 0; i <= 7; i++) { - if (channels.getByIndex(i).settings.uplink_enabled) - uplinkEnabled = true; - } - if (!uplinkEnabled) - return; // no channels have an uplink enabled - auto &ch = channels.getByIndex(chIndex); + if (mp.via_mqtt) + return; // Don't send messages that came from MQTT back into MQTT + bool uplinkEnabled = false; + for (int i = 0; i <= 7; i++) + { + if (channels.getByIndex(i).settings.uplink_enabled) + uplinkEnabled = true; + } + if (!uplinkEnabled) + return; // no channels have an uplink enabled + auto &ch = channels.getByIndex(chIndex); - if (!mp.pki_encrypted) { - if (mp_decoded.which_payload_variant != meshtastic_MeshPacket_decoded_tag) { - LOG_CRIT("MQTT::onSend(): mp_decoded isn't actually decoded\n"); - return; - } + if (!mp.pki_encrypted) + { + if (mp_decoded.which_payload_variant != meshtastic_MeshPacket_decoded_tag) + { + LOG_CRIT("MQTT::onSend(): mp_decoded isn't actually decoded\n"); + return; + } - // check for the lowest bit of the data bitfield set false, and the use of one of the default keys. - if (mp_decoded.from != nodeDB->getNodeNum() && mp_decoded.decoded.has_bitfield && - !(mp_decoded.decoded.bitfield & BITFIELD_OK_TO_MQTT_MASK) && - (ch.settings.psk.size < 2 || (ch.settings.psk.size == 16 && memcmp(ch.settings.psk.bytes, defaultpsk, 16)) || - (ch.settings.psk.size == 32 && memcmp(ch.settings.psk.bytes, eventpsk, 32)))) { - LOG_INFO("MQTT onSend - Not forwarding packet due to DontMqttMeBro flag\n"); - return; - } + // check for the lowest bit of the data bitfield set false, and the use of one of the default keys. + if (mp_decoded.from != nodeDB->getNodeNum() && mp_decoded.decoded.has_bitfield && + !(mp_decoded.decoded.bitfield & BITFIELD_OK_TO_MQTT_MASK) && + (ch.settings.psk.size < 2 || (ch.settings.psk.size == 16 && memcmp(ch.settings.psk.bytes, defaultpsk, 16)) || + (ch.settings.psk.size == 32 && memcmp(ch.settings.psk.bytes, eventpsk, 32)))) + { + LOG_INFO("MQTT onSend - Not forwarding packet due to DontMqttMeBro flag\n"); + return; + } - if (strcmp(moduleConfig.mqtt.address, default_mqtt_address) == 0 && - (mp_decoded.decoded.portnum == meshtastic_PortNum_RANGE_TEST_APP || - mp_decoded.decoded.portnum == meshtastic_PortNum_DETECTION_SENSOR_APP)) { - LOG_DEBUG("MQTT onSend - Ignoring range test or detection sensor message on public mqtt\n"); - return; - } - } - if (mp.pki_encrypted || ch.settings.uplink_enabled) { - const char *channelId = mp.pki_encrypted ? "PKI" : channels.getGlobalId(chIndex); + if (strcmp(moduleConfig.mqtt.address, default_mqtt_address) == 0 && + (mp_decoded.decoded.portnum == meshtastic_PortNum_RANGE_TEST_APP || + mp_decoded.decoded.portnum == meshtastic_PortNum_DETECTION_SENSOR_APP)) + { + LOG_DEBUG("MQTT onSend - Ignoring range test or detection sensor message on public mqtt\n"); + return; + } + } + if (mp.pki_encrypted || ch.settings.uplink_enabled) + { + const char *channelId = mp.pki_encrypted ? "PKI" : channels.getGlobalId(chIndex); - meshtastic_ServiceEnvelope *env = mqttPool.allocZeroed(); - env->channel_id = (char *)channelId; - env->gateway_id = owner.id; + meshtastic_ServiceEnvelope *env = mqttPool.allocZeroed(); + env->channel_id = (char *)channelId; + env->gateway_id = owner.id; - LOG_DEBUG("MQTT onSend - Publishing "); - if (moduleConfig.mqtt.encryption_enabled) { - env->packet = (meshtastic_MeshPacket *)∓ - LOG_DEBUG("encrypted message\n"); - } else if (mp_decoded.which_payload_variant == - meshtastic_MeshPacket_decoded_tag) { // Don't upload a still-encrypted PKI packet - env->packet = (meshtastic_MeshPacket *)&mp_decoded; - LOG_DEBUG("portnum %i message\n", env->packet->decoded.portnum); - } + LOG_DEBUG("MQTT onSend - Publishing "); + if (moduleConfig.mqtt.encryption_enabled) + { + env->packet = (meshtastic_MeshPacket *)∓ + LOG_DEBUG("encrypted message\n"); + } + else if (mp_decoded.which_payload_variant == + meshtastic_MeshPacket_decoded_tag) + { // Don't upload a still-encrypted PKI packet + env->packet = (meshtastic_MeshPacket *)&mp_decoded; + LOG_DEBUG("portnum %i message\n", env->packet->decoded.portnum); + } - if (moduleConfig.mqtt.proxy_to_client_enabled || this->isConnectedDirectly()) { - // FIXME - this size calculation is super sloppy, but it will go away once we dynamically alloc meshpackets - static uint8_t bytes[meshtastic_MeshPacket_size + 64]; - size_t numBytes = pb_encode_to_bytes(bytes, sizeof(bytes), &meshtastic_ServiceEnvelope_msg, env); - std::string topic = cryptTopic + channelId + "/" + owner.id; - LOG_DEBUG("MQTT Publish %s, %u bytes\n", topic.c_str(), numBytes); + if (moduleConfig.mqtt.proxy_to_client_enabled || this->isConnectedDirectly()) + { + // FIXME - this size calculation is super sloppy, but it will go away once we dynamically alloc meshpackets + static uint8_t bytes[meshtastic_MeshPacket_size + 64]; + size_t numBytes = pb_encode_to_bytes(bytes, sizeof(bytes), &meshtastic_ServiceEnvelope_msg, env); + std::string topic = cryptTopic + channelId + "/" + owner.id; + LOG_DEBUG("MQTT Publish %s, %u bytes\n", topic.c_str(), numBytes); - publish(topic.c_str(), bytes, numBytes, false); + publish(topic.c_str(), bytes, numBytes, false); -#if !defined(ARCH_NRF52) || defined(NRF52_USE_JSON) // JSON is not supported on nRF52, see issue #2804 ### Fixed by using ArduinoJson ### - if (moduleConfig.mqtt.json_enabled) { - // handle json topic - auto jsonString = MeshPacketSerializer::JsonSerialize((meshtastic_MeshPacket *)&mp_decoded); - if (jsonString.length() != 0) { - std::string topicJson = jsonTopic + channelId + "/" + owner.id; - LOG_INFO("JSON publish message to %s, %u bytes: %s\n", topicJson.c_str(), jsonString.length(), - jsonString.c_str()); - publish(topicJson.c_str(), jsonString.c_str(), false); - } - } +#if !defined(ARCH_NRF52) || defined(NRF52_USE_JSON) // JSON is not supported on nRF52, see issue #2804 ### Fixed by using ArduinoJson ### + if (moduleConfig.mqtt.json_enabled) + { + // handle json topic + auto jsonString = MeshPacketSerializer::JsonSerialize((meshtastic_MeshPacket *)&mp_decoded); + if (jsonString.length() != 0) + { + std::string topicJson = jsonTopic + channelId + "/" + owner.id; + LOG_INFO("JSON publish message to %s, %u bytes: %s\n", topicJson.c_str(), jsonString.length(), + jsonString.c_str()); + publish(topicJson.c_str(), jsonString.c_str(), false); + } + } #endif // ARCH_NRF52 NRF52_USE_JSON - } else { - LOG_INFO("MQTT not connected, queueing packet\n"); - if (mqttQueue.numFree() == 0) { - LOG_WARN("NOTE: MQTT queue is full, discarding oldest\n"); - meshtastic_ServiceEnvelope *d = mqttQueue.dequeuePtr(0); - if (d) - mqttPool.release(d); - } - // make a copy of serviceEnvelope and queue it - meshtastic_ServiceEnvelope *copied = mqttPool.allocCopy(*env); - assert(mqttQueue.enqueue(copied, 0)); - } - mqttPool.release(env); - } + } + else + { + LOG_INFO("MQTT not connected, queueing packet\n"); + if (mqttQueue.numFree() == 0) + { + LOG_WARN("NOTE: MQTT queue is full, discarding oldest\n"); + meshtastic_ServiceEnvelope *d = mqttQueue.dequeuePtr(0); + if (d) + mqttPool.release(d); + } + // make a copy of serviceEnvelope and queue it + meshtastic_ServiceEnvelope *copied = mqttPool.allocCopy(*env); + assert(mqttQueue.enqueue(copied, 0)); + } + mqttPool.release(env); + } } void MQTT::perhapsReportToMap() { - if (!moduleConfig.mqtt.map_reporting_enabled || !(moduleConfig.mqtt.proxy_to_client_enabled || isConnectedDirectly())) - return; + if (!moduleConfig.mqtt.map_reporting_enabled || !(moduleConfig.mqtt.proxy_to_client_enabled || isConnectedDirectly())) + return; - if (millis() - last_report_to_map < map_publish_interval_msecs) { - return; - } else { - if (map_position_precision == 0 || (localPosition.latitude_i == 0 && localPosition.longitude_i == 0)) { - last_report_to_map = millis(); - if (map_position_precision == 0) - LOG_WARN("MQTT Map reporting is enabled, but precision is 0\n"); - if (localPosition.latitude_i == 0 && localPosition.longitude_i == 0) - LOG_WARN("MQTT Map reporting is enabled, but no position available.\n"); - return; - } + if (millis() - last_report_to_map < map_publish_interval_msecs) + { + return; + } + else + { + if (map_position_precision == 0 || (localPosition.latitude_i == 0 && localPosition.longitude_i == 0)) + { + last_report_to_map = millis(); + if (map_position_precision == 0) + LOG_WARN("MQTT Map reporting is enabled, but precision is 0\n"); + if (localPosition.latitude_i == 0 && localPosition.longitude_i == 0) + LOG_WARN("MQTT Map reporting is enabled, but no position available.\n"); + return; + } - // Allocate ServiceEnvelope and fill it - meshtastic_ServiceEnvelope *se = mqttPool.allocZeroed(); - se->channel_id = (char *)channels.getGlobalId(channels.getPrimaryIndex()); // Use primary channel as the channel_id - se->gateway_id = owner.id; + // Allocate ServiceEnvelope and fill it + meshtastic_ServiceEnvelope *se = mqttPool.allocZeroed(); + se->channel_id = (char *)channels.getGlobalId(channels.getPrimaryIndex()); // Use primary channel as the channel_id + se->gateway_id = owner.id; - // Allocate MeshPacket and fill it - meshtastic_MeshPacket *mp = packetPool.allocZeroed(); - mp->which_payload_variant = meshtastic_MeshPacket_decoded_tag; - mp->from = nodeDB->getNodeNum(); - mp->to = NODENUM_BROADCAST; - mp->decoded.portnum = meshtastic_PortNum_MAP_REPORT_APP; + // Allocate MeshPacket and fill it + meshtastic_MeshPacket *mp = packetPool.allocZeroed(); + mp->which_payload_variant = meshtastic_MeshPacket_decoded_tag; + mp->from = nodeDB->getNodeNum(); + mp->to = NODENUM_BROADCAST; + mp->decoded.portnum = meshtastic_PortNum_MAP_REPORT_APP; - // Fill MapReport message - meshtastic_MapReport mapReport = meshtastic_MapReport_init_default; - memcpy(mapReport.long_name, owner.long_name, sizeof(owner.long_name)); - memcpy(mapReport.short_name, owner.short_name, sizeof(owner.short_name)); - mapReport.role = config.device.role; - mapReport.hw_model = owner.hw_model; - strncpy(mapReport.firmware_version, optstr(APP_VERSION), sizeof(mapReport.firmware_version)); - mapReport.region = config.lora.region; - mapReport.modem_preset = config.lora.modem_preset; - mapReport.has_default_channel = channels.hasDefaultChannel(); + // Fill MapReport message + meshtastic_MapReport mapReport = meshtastic_MapReport_init_default; + memcpy(mapReport.long_name, owner.long_name, sizeof(owner.long_name)); + memcpy(mapReport.short_name, owner.short_name, sizeof(owner.short_name)); + mapReport.role = config.device.role; + mapReport.hw_model = owner.hw_model; + strncpy(mapReport.firmware_version, optstr(APP_VERSION), sizeof(mapReport.firmware_version)); + mapReport.region = config.lora.region; + mapReport.modem_preset = config.lora.modem_preset; + mapReport.has_default_channel = channels.hasDefaultChannel(); - // Set position with precision (same as in PositionModule) - if (map_position_precision < 32 && map_position_precision > 0) { - mapReport.latitude_i = localPosition.latitude_i & (UINT32_MAX << (32 - map_position_precision)); - mapReport.longitude_i = localPosition.longitude_i & (UINT32_MAX << (32 - map_position_precision)); - mapReport.latitude_i += (1 << (31 - map_position_precision)); - mapReport.longitude_i += (1 << (31 - map_position_precision)); - } else { - mapReport.latitude_i = localPosition.latitude_i; - mapReport.longitude_i = localPosition.longitude_i; - } - mapReport.altitude = localPosition.altitude; - mapReport.position_precision = map_position_precision; + // Set position with precision (same as in PositionModule) + if (map_position_precision < 32 && map_position_precision > 0) + { + mapReport.latitude_i = localPosition.latitude_i & (UINT32_MAX << (32 - map_position_precision)); + mapReport.longitude_i = localPosition.longitude_i & (UINT32_MAX << (32 - map_position_precision)); + mapReport.latitude_i += (1 << (31 - map_position_precision)); + mapReport.longitude_i += (1 << (31 - map_position_precision)); + } + else + { + mapReport.latitude_i = localPosition.latitude_i; + mapReport.longitude_i = localPosition.longitude_i; + } + mapReport.altitude = localPosition.altitude; + mapReport.position_precision = map_position_precision; - mapReport.num_online_local_nodes = nodeDB->getNumOnlineMeshNodes(true); + mapReport.num_online_local_nodes = nodeDB->getNumOnlineMeshNodes(true); - // Encode MapReport message and set it to MeshPacket in ServiceEnvelope - mp->decoded.payload.size = pb_encode_to_bytes(mp->decoded.payload.bytes, sizeof(mp->decoded.payload.bytes), - &meshtastic_MapReport_msg, &mapReport); - se->packet = mp; + // Encode MapReport message and set it to MeshPacket in ServiceEnvelope + mp->decoded.payload.size = pb_encode_to_bytes(mp->decoded.payload.bytes, sizeof(mp->decoded.payload.bytes), + &meshtastic_MapReport_msg, &mapReport); + se->packet = mp; - // FIXME - this size calculation is super sloppy, but it will go away once we dynamically alloc meshpackets - static uint8_t bytes[meshtastic_MeshPacket_size + 64]; - size_t numBytes = pb_encode_to_bytes(bytes, sizeof(bytes), &meshtastic_ServiceEnvelope_msg, se); + // FIXME - this size calculation is super sloppy, but it will go away once we dynamically alloc meshpackets + static uint8_t bytes[meshtastic_MeshPacket_size + 64]; + size_t numBytes = pb_encode_to_bytes(bytes, sizeof(bytes), &meshtastic_ServiceEnvelope_msg, se); - LOG_INFO("MQTT Publish map report to %s\n", mapTopic.c_str()); - publish(mapTopic.c_str(), bytes, numBytes, false); + LOG_INFO("MQTT Publish map report to %s\n", mapTopic.c_str()); + publish(mapTopic.c_str(), bytes, numBytes, false); - // Release the allocated memory for ServiceEnvelope and MeshPacket - mqttPool.release(se); - packetPool.release(mp); + // Release the allocated memory for ServiceEnvelope and MeshPacket + mqttPool.release(se); + packetPool.release(mp); - // Update the last report time - last_report_to_map = millis(); - } + // Update the last report time + last_report_to_map = millis(); + } } bool MQTT::isValidJsonEnvelope(JSONObject &json) { - // if "sender" is provided, avoid processing packets we uplinked - return (json.find("sender") != json.end() ? (json["sender"]->AsString().compare(owner.id) != 0) : true) && - (json.find("hopLimit") != json.end() ? json["hopLimit"]->IsNumber() : true) && // hop limit should be a number - (json.find("from") != json.end()) && json["from"]->IsNumber() && - (json["from"]->AsNumber() == nodeDB->getNodeNum()) && // only accept message if the "from" is us - (json.find("type") != json.end()) && json["type"]->IsString() && // should specify a type - (json.find("payload") != json.end()); // should have a payload + // if "sender" is provided, avoid processing packets we uplinked + return (json.find("sender") != json.end() ? (json["sender"]->AsString().compare(owner.id) != 0) : true) && + (json.find("hopLimit") != json.end() ? json["hopLimit"]->IsNumber() : true) && // hop limit should be a number + (json.find("from") != json.end()) && json["from"]->IsNumber() && + (json["from"]->AsNumber() == nodeDB->getNodeNum()) && // only accept message if the "from" is us + (json.find("type") != json.end()) && json["type"]->IsString() && // should specify a type + (json.find("payload") != json.end()); // should have a payload } diff --git a/src/platform/nrf52/NRF52Bluetooth.cpp b/src/platform/nrf52/NRF52Bluetooth.cpp index 177255b2f..9ed2a0d6a 100644 --- a/src/platform/nrf52/NRF52Bluetooth.cpp +++ b/src/platform/nrf52/NRF52Bluetooth.cpp @@ -19,7 +19,7 @@ static BLEBas blebas; // BAS (Battery Service) helper class instance #ifndef BLE_DFU_SECURE static BLEDfu bledfu; // DFU software update helper service #else -static BLEDfuSecure bledfusecure; // DFU software update helper service +static BLEDfuSecure bledfusecure; // DFU software update helper service #endif // This scratch buffer is used for various bluetooth reads/writes - but it is safe because only one bt operation can be in @@ -32,23 +32,23 @@ static uint16_t connectionHandle; class BluetoothPhoneAPI : public PhoneAPI { - /** - * Subclasses can use this as a hook to provide custom notifications for their transport (i.e. bluetooth notifies) - */ - virtual void onNowHasData(uint32_t fromRadioNum) override - { - PhoneAPI::onNowHasData(fromRadioNum); + /** + * Subclasses can use this as a hook to provide custom notifications for their transport (i.e. bluetooth notifies) + */ + virtual void onNowHasData(uint32_t fromRadioNum) override + { + PhoneAPI::onNowHasData(fromRadioNum); - LOG_INFO("BLE notify fromNum\n"); - fromNum.notify32(fromRadioNum); - } + LOG_INFO("BLE notify fromNum\n"); + fromNum.notify32(fromRadioNum); + } - /// Check the current underlying physical link to see if the client is currently connected - virtual bool checkIsConnected() override - { - BLEConnection *connection = Bluefruit.Connection(connectionHandle); - return connection->connected(); - } + /// Check the current underlying physical link to see if the client is currently connected + virtual bool checkIsConnected() override + { + BLEConnection *connection = Bluefruit.Connection(connectionHandle); + return connection->connected(); + } }; static BluetoothPhoneAPI *bluetoothPhoneAPI; @@ -56,12 +56,12 @@ static BluetoothPhoneAPI *bluetoothPhoneAPI; void onConnect(uint16_t conn_handle) { - // Get the reference to current connection - BLEConnection *connection = Bluefruit.Connection(conn_handle); - connectionHandle = conn_handle; - char central_name[32] = {0}; - connection->getPeerName(central_name, sizeof(central_name)); - LOG_INFO("BLE Connected to %s\n", central_name); + // Get the reference to current connection + BLEConnection *connection = Bluefruit.Connection(conn_handle); + connectionHandle = conn_handle; + char central_name[32] = {0}; + connection->getPeerName(central_name, sizeof(central_name)); + LOG_INFO("BLE Connected to %s\n", central_name); } /** * Callback invoked when a connection is dropped @@ -70,246 +70,258 @@ void onConnect(uint16_t conn_handle) */ void onDisconnect(uint16_t conn_handle, uint8_t reason) { - // FIXME - we currently assume only one active connection - LOG_INFO("BLE Disconnected, reason = 0x%x\n", reason); + // FIXME - we currently assume only one active connection + LOG_INFO("BLE Disconnected, reason = 0x%x\n", reason); } void onCccd(uint16_t conn_hdl, BLECharacteristic *chr, uint16_t cccd_value) { - // Display the raw request packet - LOG_INFO("CCCD Updated: %u\n", cccd_value); - // Check the characteristic this CCCD update is associated with in case - // this handler is used for multiple CCCD records. + // Display the raw request packet + LOG_INFO("CCCD Updated: %u\n", cccd_value); + // Check the characteristic this CCCD update is associated with in case + // this handler is used for multiple CCCD records. - // According to the GATT spec: cccd value = 0x0001 means notifications are enabled - // and cccd value = 0x0002 means indications are enabled + // According to the GATT spec: cccd value = 0x0001 means notifications are enabled + // and cccd value = 0x0002 means indications are enabled - if (chr->uuid == fromNum.uuid || chr->uuid == logRadio.uuid) { - auto result = cccd_value == 2 ? chr->indicateEnabled(conn_hdl) : chr->notifyEnabled(conn_hdl); - if (result) { - LOG_INFO("Notify/Indicate enabled\n"); - } else { - LOG_INFO("Notify/Indicate disabled\n"); - } - } + if (chr->uuid == fromNum.uuid || chr->uuid == logRadio.uuid) + { + auto result = cccd_value == 2 ? chr->indicateEnabled(conn_hdl) : chr->notifyEnabled(conn_hdl); + if (result) + { + LOG_INFO("Notify/Indicate enabled\n"); + } + else + { + LOG_INFO("Notify/Indicate disabled\n"); + } + } } void startAdv(void) { - // Advertising packet - Bluefruit.Advertising.addFlags(BLE_GAP_ADV_FLAGS_LE_ONLY_GENERAL_DISC_MODE); - // IncludeService UUID - // Bluefruit.ScanResponse.addService(meshBleService); - Bluefruit.ScanResponse.addTxPower(); - Bluefruit.ScanResponse.addName(); - // Include Name - // Bluefruit.Advertising.addName(); - Bluefruit.Advertising.addService(meshBleService); - /* Start Advertising - * - Enable auto advertising if disconnected - * - Interval: fast mode = 20 ms, slow mode = 152.5 ms - * - Timeout for fast mode is 30 seconds - * - Start(timeout) with timeout = 0 will advertise forever (until connected) - * - * For recommended advertising interval - * https://developer.apple.com/library/content/qa/qa1931/_index.html - */ - Bluefruit.Advertising.restartOnDisconnect(true); - Bluefruit.Advertising.setInterval(32, 244); // in unit of 0.625 ms - Bluefruit.Advertising.setFastTimeout(30); // number of seconds in fast mode - Bluefruit.Advertising.start(0); // 0 = Don't stop advertising after n seconds. FIXME, we should stop advertising after X + // Advertising packet + Bluefruit.Advertising.addFlags(BLE_GAP_ADV_FLAGS_LE_ONLY_GENERAL_DISC_MODE); + // IncludeService UUID + // Bluefruit.ScanResponse.addService(meshBleService); + Bluefruit.ScanResponse.addTxPower(); + Bluefruit.ScanResponse.addName(); + // Include Name + // Bluefruit.Advertising.addName(); + Bluefruit.Advertising.addService(meshBleService); + /* Start Advertising + * - Enable auto advertising if disconnected + * - Interval: fast mode = 20 ms, slow mode = 152.5 ms + * - Timeout for fast mode is 30 seconds + * - Start(timeout) with timeout = 0 will advertise forever (until connected) + * + * For recommended advertising interval + * https://developer.apple.com/library/content/qa/qa1931/_index.html + */ + Bluefruit.Advertising.restartOnDisconnect(true); + Bluefruit.Advertising.setInterval(32, 244); // in unit of 0.625 ms + Bluefruit.Advertising.setFastTimeout(30); // number of seconds in fast mode + Bluefruit.Advertising.start(0); // 0 = Don't stop advertising after n seconds. FIXME, we should stop advertising after X } // Just ack that the caller is allowed to read static void authorizeRead(uint16_t conn_hdl) { - ble_gatts_rw_authorize_reply_params_t reply = {.type = BLE_GATTS_AUTHORIZE_TYPE_READ}; - reply.params.write.gatt_status = BLE_GATT_STATUS_SUCCESS; - sd_ble_gatts_rw_authorize_reply(conn_hdl, &reply); + ble_gatts_rw_authorize_reply_params_t reply = {.type = BLE_GATTS_AUTHORIZE_TYPE_READ}; + reply.params.write.gatt_status = BLE_GATT_STATUS_SUCCESS; + sd_ble_gatts_rw_authorize_reply(conn_hdl, &reply); } /** * client is starting read, pull the bytes from our API class */ void onFromRadioAuthorize(uint16_t conn_hdl, BLECharacteristic *chr, ble_gatts_evt_read_t *request) { - if (request->offset == 0) { - // If the read is long, we will get multiple authorize invocations - we only populate data on the first - size_t numBytes = bluetoothPhoneAPI->getFromRadio(fromRadioBytes); - // Someone is going to read our value as soon as this callback returns. So fill it with the next message in the queue - // or make empty if the queue is empty - fromRadio.write(fromRadioBytes, numBytes); - } else { - // LOG_INFO("Ignoring successor read\n"); - } - authorizeRead(conn_hdl); + if (request->offset == 0) + { + // If the read is long, we will get multiple authorize invocations - we only populate data on the first + size_t numBytes = bluetoothPhoneAPI->getFromRadio(fromRadioBytes); + // Someone is going to read our value as soon as this callback returns. So fill it with the next message in the queue + // or make empty if the queue is empty + fromRadio.write(fromRadioBytes, numBytes); + } + else + { + // LOG_INFO("Ignoring successor read\n"); + } + authorizeRead(conn_hdl); } void onToRadioWrite(uint16_t conn_hdl, BLECharacteristic *chr, uint8_t *data, uint16_t len) { - LOG_INFO("toRadioWriteCb data %p, len %u\n", data, len); - bluetoothPhoneAPI->handleToRadio(data, len); + LOG_INFO("toRadioWriteCb data %p, len %u\n", data, len); + bluetoothPhoneAPI->handleToRadio(data, len); } void setupMeshService(void) { - bluetoothPhoneAPI = new BluetoothPhoneAPI(); - meshBleService.begin(); - // Note: You must call .begin() on the BLEService before calling .begin() on - // any characteristic(s) within that service definition.. Calling .begin() on - // a BLECharacteristic will cause it to be added to the last BLEService that - // was 'begin()'ed! - auto secMode = - config.bluetooth.mode == meshtastic_Config_BluetoothConfig_PairingMode_NO_PIN ? SECMODE_OPEN : SECMODE_ENC_NO_MITM; - fromNum.setProperties(CHR_PROPS_NOTIFY | CHR_PROPS_READ); - fromNum.setPermission(secMode, SECMODE_NO_ACCESS); // FIXME, secure this!!! - fromNum.setFixedLen( - 0); // Variable len (either 0 or 4) FIXME consider changing protocol so it is fixed 4 byte len, where 0 means empty - fromNum.setMaxLen(4); - fromNum.setCccdWriteCallback(onCccd); // Optionally capture CCCD updates - // We don't yet need to hook the fromNum auth callback - // fromNum.setReadAuthorizeCallback(fromNumAuthorizeCb); - fromNum.write32(0); // Provide default fromNum of 0 - fromNum.begin(); + bluetoothPhoneAPI = new BluetoothPhoneAPI(); + meshBleService.begin(); + // Note: You must call .begin() on the BLEService before calling .begin() on + // any characteristic(s) within that service definition.. Calling .begin() on + // a BLECharacteristic will cause it to be added to the last BLEService that + // was 'begin()'ed! + auto secMode = + config.bluetooth.mode == meshtastic_Config_BluetoothConfig_PairingMode_NO_PIN ? SECMODE_OPEN : SECMODE_ENC_NO_MITM; + fromNum.setProperties(CHR_PROPS_NOTIFY | CHR_PROPS_READ); + fromNum.setPermission(secMode, SECMODE_NO_ACCESS); // FIXME, secure this!!! + fromNum.setFixedLen( + 0); // Variable len (either 0 or 4) FIXME consider changing protocol so it is fixed 4 byte len, where 0 means empty + fromNum.setMaxLen(4); + fromNum.setCccdWriteCallback(onCccd); // Optionally capture CCCD updates + // We don't yet need to hook the fromNum auth callback + // fromNum.setReadAuthorizeCallback(fromNumAuthorizeCb); + fromNum.write32(0); // Provide default fromNum of 0 + fromNum.begin(); - fromRadio.setProperties(CHR_PROPS_READ); - fromRadio.setPermission(secMode, SECMODE_NO_ACCESS); - fromRadio.setMaxLen(sizeof(fromRadioBytes)); - fromRadio.setReadAuthorizeCallback( - onFromRadioAuthorize, - false); // We don't call this callback via the adafruit queue, because we can safely run in the BLE context - fromRadio.setBuffer(fromRadioBytes, sizeof(fromRadioBytes)); // we preallocate our fromradio buffer so we won't waste space - // for two copies - fromRadio.begin(); + fromRadio.setProperties(CHR_PROPS_READ); + fromRadio.setPermission(secMode, SECMODE_NO_ACCESS); + fromRadio.setMaxLen(sizeof(fromRadioBytes)); + fromRadio.setReadAuthorizeCallback( + onFromRadioAuthorize, + false); // We don't call this callback via the adafruit queue, because we can safely run in the BLE context + fromRadio.setBuffer(fromRadioBytes, sizeof(fromRadioBytes)); // we preallocate our fromradio buffer so we won't waste space + // for two copies + fromRadio.begin(); - toRadio.setProperties(CHR_PROPS_WRITE); - toRadio.setPermission(secMode, secMode); // FIXME secure this! - toRadio.setFixedLen(0); - toRadio.setMaxLen(512); - toRadio.setBuffer(toRadioBytes, sizeof(toRadioBytes)); - // We don't call this callback via the adafruit queue, because we can safely run in the BLE context - toRadio.setWriteCallback(onToRadioWrite, false); - toRadio.begin(); + toRadio.setProperties(CHR_PROPS_WRITE); + toRadio.setPermission(secMode, secMode); // FIXME secure this! + toRadio.setFixedLen(0); + toRadio.setMaxLen(512); + toRadio.setBuffer(toRadioBytes, sizeof(toRadioBytes)); + // We don't call this callback via the adafruit queue, because we can safely run in the BLE context + toRadio.setWriteCallback(onToRadioWrite, false); + toRadio.begin(); - logRadio.setProperties(CHR_PROPS_INDICATE | CHR_PROPS_NOTIFY | CHR_PROPS_READ); - logRadio.setPermission(secMode, SECMODE_NO_ACCESS); - logRadio.setMaxLen(512); - logRadio.setCccdWriteCallback(onCccd); - logRadio.write32(0); - logRadio.begin(); + logRadio.setProperties(CHR_PROPS_INDICATE | CHR_PROPS_NOTIFY | CHR_PROPS_READ); + logRadio.setPermission(secMode, SECMODE_NO_ACCESS); + logRadio.setMaxLen(512); + logRadio.setCccdWriteCallback(onCccd); + logRadio.write32(0); + logRadio.begin(); } static uint32_t configuredPasskey; void NRF52Bluetooth::shutdown() { - // Shutdown bluetooth for minimum power draw - LOG_INFO("Disable NRF52 bluetooth\n"); - uint8_t connection_num = Bluefruit.connected(); - if (connection_num) { - for (uint8_t i = 0; i < connection_num; i++) { - LOG_INFO("NRF52 bluetooth disconnecting handle %d\n", i); - Bluefruit.disconnect(i); - } - delay(100); // wait for ondisconnect; - } - Bluefruit.Advertising.stop(); + // Shutdown bluetooth for minimum power draw + LOG_INFO("Disable NRF52 bluetooth\n"); + uint8_t connection_num = Bluefruit.connected(); + if (connection_num) + { + for (uint8_t i = 0; i < connection_num; i++) + { + LOG_INFO("NRF52 bluetooth disconnecting handle %d\n", i); + Bluefruit.disconnect(i); + } + delay(100); // wait for ondisconnect; + } + Bluefruit.Advertising.stop(); } void NRF52Bluetooth::startDisabled() { - // Setup Bluetooth - nrf52Bluetooth->setup(); - // Shutdown bluetooth for minimum power draw - Bluefruit.Advertising.stop(); - Bluefruit.setTxPower(-40); // Minimum power - LOG_INFO("Disabling NRF52 Bluetooth. (Workaround: tx power min, advertising stopped)\n"); + // Setup Bluetooth + nrf52Bluetooth->setup(); + // Shutdown bluetooth for minimum power draw + Bluefruit.Advertising.stop(); + Bluefruit.setTxPower(-40); // Minimum power + LOG_INFO("Disabling NRF52 Bluetooth. (Workaround: tx power min, advertising stopped)\n"); } bool NRF52Bluetooth::isConnected() { - return Bluefruit.connected(connectionHandle); + return Bluefruit.connected(connectionHandle); } int NRF52Bluetooth::getRssi() { - return 0; // FIXME figure out where to source this + return 0; // FIXME figure out where to source this } void NRF52Bluetooth::setup() { - // Initialise the Bluefruit module - LOG_INFO("Initialize the Bluefruit nRF52 module\n"); - Bluefruit.autoConnLed(false); - Bluefruit.configPrphBandwidth(BANDWIDTH_MAX); - Bluefruit.begin(); - // Clear existing data. - Bluefruit.Advertising.stop(); - Bluefruit.Advertising.clearData(); - Bluefruit.ScanResponse.clearData(); - if (config.bluetooth.mode != meshtastic_Config_BluetoothConfig_PairingMode_NO_PIN) { - configuredPasskey = config.bluetooth.mode == meshtastic_Config_BluetoothConfig_PairingMode_FIXED_PIN - ? config.bluetooth.fixed_pin - : random(100000, 999999); - auto pinString = std::to_string(configuredPasskey); - LOG_INFO("Bluetooth pin set to '%i'\n", configuredPasskey); - Bluefruit.Security.setPIN(pinString.c_str()); - Bluefruit.Security.setIOCaps(true, false, false); - Bluefruit.Security.setPairPasskeyCallback(NRF52Bluetooth::onPairingPasskey); - Bluefruit.Security.setPairCompleteCallback(NRF52Bluetooth::onPairingCompleted); - Bluefruit.Security.setSecuredCallback(NRF52Bluetooth::onConnectionSecured); - meshBleService.setPermission(SECMODE_ENC_WITH_MITM, SECMODE_ENC_WITH_MITM); - } else { - Bluefruit.Security.setIOCaps(false, false, false); - meshBleService.setPermission(SECMODE_OPEN, SECMODE_OPEN); - } - // Set the advertised device name (keep it short!) - Bluefruit.setName(getDeviceName()); - // Set the connect/disconnect callback handlers - Bluefruit.Periph.setConnectCallback(onConnect); - Bluefruit.Periph.setDisconnectCallback(onDisconnect); + // Initialise the Bluefruit module + LOG_INFO("Initialize the Bluefruit nRF52 module\n"); + Bluefruit.autoConnLed(false); + Bluefruit.configPrphBandwidth(BANDWIDTH_MAX); + Bluefruit.begin(); + // Clear existing data. + Bluefruit.Advertising.stop(); + Bluefruit.Advertising.clearData(); + Bluefruit.ScanResponse.clearData(); + if (config.bluetooth.mode != meshtastic_Config_BluetoothConfig_PairingMode_NO_PIN) + { + configuredPasskey = config.bluetooth.mode == meshtastic_Config_BluetoothConfig_PairingMode_FIXED_PIN + ? config.bluetooth.fixed_pin + : random(100000, 999999); + auto pinString = std::to_string(configuredPasskey); + LOG_INFO("Bluetooth pin set to '%i'\n", configuredPasskey); + Bluefruit.Security.setPIN(pinString.c_str()); + Bluefruit.Security.setIOCaps(true, false, false); + Bluefruit.Security.setPairPasskeyCallback(NRF52Bluetooth::onPairingPasskey); + Bluefruit.Security.setPairCompleteCallback(NRF52Bluetooth::onPairingCompleted); + Bluefruit.Security.setSecuredCallback(NRF52Bluetooth::onConnectionSecured); + meshBleService.setPermission(SECMODE_ENC_WITH_MITM, SECMODE_ENC_WITH_MITM); + } + else + { + Bluefruit.Security.setIOCaps(false, false, false); + meshBleService.setPermission(SECMODE_OPEN, SECMODE_OPEN); + } + // Set the advertised device name (keep it short!) + Bluefruit.setName(getDeviceName()); + // Set the connect/disconnect callback handlers + Bluefruit.Periph.setConnectCallback(onConnect); + Bluefruit.Periph.setDisconnectCallback(onDisconnect); #ifndef BLE_DFU_SECURE - bledfu.setPermission(SECMODE_ENC_WITH_MITM, SECMODE_ENC_WITH_MITM); - bledfu.begin(); // Install the DFU helper + bledfu.setPermission(SECMODE_ENC_WITH_MITM, SECMODE_ENC_WITH_MITM); + bledfu.begin(); // Install the DFU helper #else - bledfusecure.setPermission(SECMODE_ENC_WITH_MITM, SECMODE_ENC_WITH_MITM); // add by WayenWeng - bledfusecure.begin(); // Install the DFU helper + bledfusecure.setPermission(SECMODE_ENC_WITH_MITM, SECMODE_ENC_WITH_MITM); // add by WayenWeng + bledfusecure.begin(); // Install the DFU helper #endif - // Configure and Start the Device Information Service - LOG_INFO("Configuring the Device Information Service\n"); - bledis.setModel(optstr(HW_VERSION)); - bledis.setFirmwareRev(optstr(APP_VERSION)); - bledis.begin(); - // Start the BLE Battery Service and set it to 100% - LOG_INFO("Configuring the Battery Service\n"); - blebas.begin(); - blebas.write(0); // Unknown battery level for now - // Setup the Heart Rate Monitor service using - // BLEService and BLECharacteristic classes - LOG_INFO("Configuring the Mesh bluetooth service\n"); - setupMeshService(); - // Setup the advertising packet(s) - LOG_INFO("Setting up the advertising payload(s)\n"); - startAdv(); - LOG_INFO("Advertising\n"); + // Configure and Start the Device Information Service + LOG_INFO("Configuring the Device Information Service\n"); + bledis.setModel(optstr(HW_VERSION)); + bledis.setFirmwareRev(optstr(APP_VERSION)); + bledis.begin(); + // Start the BLE Battery Service and set it to 100% + LOG_INFO("Configuring the Battery Service\n"); + blebas.begin(); + blebas.write(0); // Unknown battery level for now + // Setup the Heart Rate Monitor service using + // BLEService and BLECharacteristic classes + LOG_INFO("Configuring the Mesh bluetooth service\n"); + setupMeshService(); + // Setup the advertising packet(s) + LOG_INFO("Setting up the advertising payload(s)\n"); + startAdv(); + LOG_INFO("Advertising\n"); } void NRF52Bluetooth::resumeAdvertising() { - Bluefruit.Advertising.restartOnDisconnect(true); - Bluefruit.Advertising.setInterval(32, 244); // in unit of 0.625 ms - Bluefruit.Advertising.setFastTimeout(30); // number of seconds in fast mode - Bluefruit.Advertising.start(0); + Bluefruit.Advertising.restartOnDisconnect(true); + Bluefruit.Advertising.setInterval(32, 244); // in unit of 0.625 ms + Bluefruit.Advertising.setFastTimeout(30); // number of seconds in fast mode + Bluefruit.Advertising.start(0); } /// Given a level between 0-100, update the BLE attribute void updateBatteryLevel(uint8_t level) { - blebas.write(level); + blebas.write(level); } void NRF52Bluetooth::clearBonds() { - LOG_INFO("Clearing bluetooth bonds!\n"); - bond_print_list(BLE_GAP_ROLE_PERIPH); - bond_print_list(BLE_GAP_ROLE_CENTRAL); - Bluefruit.Periph.clearBonds(); - Bluefruit.Central.clearBonds(); + LOG_INFO("Clearing bluetooth bonds!\n"); + bond_print_list(BLE_GAP_ROLE_PERIPH); + bond_print_list(BLE_GAP_ROLE_CENTRAL); + Bluefruit.Periph.clearBonds(); + Bluefruit.Central.clearBonds(); } void NRF52Bluetooth::onConnectionSecured(uint16_t conn_handle) { - LOG_INFO("BLE connection secured\n"); + LOG_INFO("BLE connection secured\n"); } bool NRF52Bluetooth::onPairingPasskey(uint16_t conn_handle, uint8_t const passkey[6], bool match_request) { - LOG_INFO("BLE pairing process started with passkey %.3s %.3s\n", passkey, passkey + 3); - powerFSM.trigger(EVENT_BLUETOOTH_PAIR); + LOG_INFO("BLE pairing process started with passkey %.3s %.3s\n", passkey, passkey + 3); + powerFSM.trigger(EVENT_BLUETOOTH_PAIR); #if !defined(MESHTASTIC_EXCLUDE_SCREEN) screen->startAlert([](OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y) -> void { @@ -337,31 +349,33 @@ bool NRF52Bluetooth::onPairingPasskey(uint16_t conn_handle, uint8_t const passke y_offset = display->height() == 64 ? y_offset + FONT_HEIGHT_LARGE - 6 : y_offset + FONT_HEIGHT_LARGE + 5; display->drawString(x_offset + x, y_offset + y, deviceName); }); #endif - if (match_request) { - uint32_t start_time = millis(); - while (millis() < start_time + 30000) { - if (!Bluefruit.connected(conn_handle)) - break; - } - } - LOG_INFO("BLE passkey pairing: match_request=%i\n", match_request); - return true; + if (match_request) + { + uint32_t start_time = millis(); + while (millis() < start_time + 30000) + { + if (!Bluefruit.connected(conn_handle)) + break; + } + } + LOG_INFO("BLE passkey pairing: match_request=%i\n", match_request); + return true; } void NRF52Bluetooth::onPairingCompleted(uint16_t conn_handle, uint8_t auth_status) { - if (auth_status == BLE_GAP_SEC_STATUS_SUCCESS) - LOG_INFO("BLE pairing success\n"); - else - LOG_INFO("BLE pairing failed\n"); - screen->endAlert(); + if (auth_status == BLE_GAP_SEC_STATUS_SUCCESS) + LOG_INFO("BLE pairing success\n"); + else + LOG_INFO("BLE pairing failed\n"); + screen->endAlert(); } void NRF52Bluetooth::sendLog(const uint8_t *logMessage, size_t length) { - if (!isConnected() || length > 512) - return; - if (logRadio.indicateEnabled()) - logRadio.indicate(logMessage, (uint16_t)length); - else - logRadio.notify(logMessage, (uint16_t)length); + if (!isConnected() || length > 512) + return; + if (logRadio.indicateEnabled()) + logRadio.indicate(logMessage, (uint16_t)length); + else + logRadio.notify(logMessage, (uint16_t)length); } \ No newline at end of file diff --git a/src/serialization/MeshPacketSerializer_nRF52.cpp b/src/serialization/MeshPacketSerializer_nRF52.cpp index 777c10ada..8c58fba27 100644 --- a/src/serialization/MeshPacketSerializer_nRF52.cpp +++ b/src/serialization/MeshPacketSerializer_nRF52.cpp @@ -16,296 +16,360 @@ StaticJsonDocument<1024> arrayObj; std::string MeshPacketSerializer::JsonSerialize(const meshtastic_MeshPacket *mp, bool shouldLog) { - // the created jsonObj is immutable after creation, so - // we need to do the heavy lifting before assembling it. - std::string msgType; + // the created jsonObj is immutable after creation, so + // we need to do the heavy lifting before assembling it. + std::string msgType; jsonObj.clear(); arrayObj.clear(); - if (mp->which_payload_variant == meshtastic_MeshPacket_decoded_tag) { - switch (mp->decoded.portnum) { - case meshtastic_PortNum_TEXT_MESSAGE_APP: { - msgType = "text"; - // convert bytes to string - if (shouldLog) - LOG_DEBUG("got text message of size %u\n", mp->decoded.payload.size); + if (mp->which_payload_variant == meshtastic_MeshPacket_decoded_tag) + { + switch (mp->decoded.portnum) + { + case meshtastic_PortNum_TEXT_MESSAGE_APP: + { + msgType = "text"; + // convert bytes to string + if (shouldLog) + LOG_DEBUG("got text message of size %u\n", mp->decoded.payload.size); - char payloadStr[(mp->decoded.payload.size) + 1]; - memcpy(payloadStr, mp->decoded.payload.bytes, mp->decoded.payload.size); - payloadStr[mp->decoded.payload.size] = 0; // null terminated string - // check if this is a JSON payload + char payloadStr[(mp->decoded.payload.size) + 1]; + memcpy(payloadStr, mp->decoded.payload.bytes, mp->decoded.payload.size); + payloadStr[mp->decoded.payload.size] = 0; // null terminated string + // check if this is a JSON payload StaticJsonDocument<512> text_doc; DeserializationError error = deserializeJson(text_doc, payloadStr); - if (error) { + if (error) + { // if it isn't, then we need to create a json object - // with the string as the value - if (shouldLog) - LOG_INFO("text message payload is of type plaintext\n"); + // with the string as the value + if (shouldLog) + LOG_INFO("text message payload is of type plaintext\n"); jsonObj["payload"]["text"] = payloadStr; - } else { + } + else + { // if it is, then we can just use the json object - if (shouldLog) - LOG_INFO("text message payload is of type json\n"); + if (shouldLog) + LOG_INFO("text message payload is of type json\n"); jsonObj["payload"] = text_doc; - } - break; - } - case meshtastic_PortNum_TELEMETRY_APP: { - msgType = "telemetry"; - meshtastic_Telemetry scratch; - meshtastic_Telemetry *decoded = NULL; - memset(&scratch, 0, sizeof(scratch)); - 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) { - jsonObj["payload"]["battery_level"] = (unsigned int)decoded->variant.device_metrics.battery_level; - jsonObj["payload"]["voltage"] = decoded->variant.device_metrics.voltage; - jsonObj["payload"]["channel_utilization"] = decoded->variant.device_metrics.channel_utilization; - jsonObj["payload"]["air_util_tx"] = decoded->variant.device_metrics.air_util_tx; - jsonObj["payload"]["uptime_seconds"] = (unsigned int)decoded->variant.device_metrics.uptime_seconds; - } else if (decoded->which_variant == meshtastic_Telemetry_environment_metrics_tag) { - jsonObj["payload"]["temperature"] = decoded->variant.environment_metrics.temperature; - jsonObj["payload"]["relative_humidity"] = decoded->variant.environment_metrics.relative_humidity; - jsonObj["payload"]["barometric_pressure"] = decoded->variant.environment_metrics.barometric_pressure; - jsonObj["payload"]["gas_resistance"] = decoded->variant.environment_metrics.gas_resistance; - jsonObj["payload"]["voltage"] = decoded->variant.environment_metrics.voltage; - jsonObj["payload"]["current"] = decoded->variant.environment_metrics.current; - jsonObj["payload"]["lux"] = decoded->variant.environment_metrics.lux; - jsonObj["payload"]["white_lux"] = decoded->variant.environment_metrics.white_lux; - jsonObj["payload"]["iaq"] = (uint)decoded->variant.environment_metrics.iaq; - jsonObj["payload"]["wind_speed"] = decoded->variant.environment_metrics.wind_speed; - jsonObj["payload"]["wind_direction"] = (uint)decoded->variant.environment_metrics.wind_direction; - jsonObj["payload"]["wind_gust"] = decoded->variant.environment_metrics.wind_gust; - jsonObj["payload"]["wind_lull"] = decoded->variant.environment_metrics.wind_lull; - } else if (decoded->which_variant == meshtastic_Telemetry_air_quality_metrics_tag) { - jsonObj["payload"]["pm10"] = (unsigned int)decoded->variant.air_quality_metrics.pm10_standard; - jsonObj["payload"]["pm25"] = (unsigned int)decoded->variant.air_quality_metrics.pm25_standard; - jsonObj["payload"]["pm100"] = (unsigned int)decoded->variant.air_quality_metrics.pm100_standard; - jsonObj["payload"]["pm10_e"] = (unsigned int)decoded->variant.air_quality_metrics.pm10_environmental; - jsonObj["payload"]["pm25_e"] = (unsigned int)decoded->variant.air_quality_metrics.pm25_environmental; - jsonObj["payload"]["pm100_e"] = (unsigned int)decoded->variant.air_quality_metrics.pm100_environmental; - } else if (decoded->which_variant == meshtastic_Telemetry_power_metrics_tag) { - jsonObj["payload"]["voltage_ch1"] = decoded->variant.power_metrics.ch1_voltage; - jsonObj["payload"]["current_ch1"] = decoded->variant.power_metrics.ch1_current; - jsonObj["payload"]["voltage_ch2"] = decoded->variant.power_metrics.ch2_voltage; - jsonObj["payload"]["current_ch2"] = decoded->variant.power_metrics.ch2_current; - jsonObj["payload"]["voltage_ch3"] = decoded->variant.power_metrics.ch3_voltage; - jsonObj["payload"]["current_ch3"] = decoded->variant.power_metrics.ch3_current; - } - } else if (shouldLog) { - LOG_ERROR("Error decoding protobuf for telemetry message!\n"); - return ""; - } - break; - } - case meshtastic_PortNum_NODEINFO_APP: { - msgType = "nodeinfo"; - meshtastic_User scratch; - meshtastic_User *decoded = NULL; - memset(&scratch, 0, sizeof(scratch)); - if (pb_decode_from_bytes(mp->decoded.payload.bytes, mp->decoded.payload.size, &meshtastic_User_msg, &scratch)) { - decoded = &scratch; - jsonObj["payload"]["id"] = decoded->id; - jsonObj["payload"]["longname"] = decoded->long_name; - jsonObj["payload"]["shortname"] = decoded->short_name; - jsonObj["payload"]["hardware"] = decoded->hw_model; - jsonObj["payload"]["role"] = (int)decoded->role; - } else if (shouldLog) { - LOG_ERROR("Error decoding protobuf for nodeinfo message!\n"); - return ""; - } - break; - } - case meshtastic_PortNum_POSITION_APP: { - msgType = "position"; - meshtastic_Position scratch; - meshtastic_Position *decoded = NULL; - memset(&scratch, 0, sizeof(scratch)); - if (pb_decode_from_bytes(mp->decoded.payload.bytes, mp->decoded.payload.size, &meshtastic_Position_msg, &scratch)) { - decoded = &scratch; - if ((int)decoded->time) { - jsonObj["payload"]["time"] = (unsigned int)decoded->time; - } - if ((int)decoded->timestamp) { - jsonObj["payload"]["timestamp"] = (unsigned int)decoded->timestamp; - } - jsonObj["payload"]["latitude_i"] = (int)decoded->latitude_i; - jsonObj["payload"]["longitude_i"] = (int)decoded->longitude_i; - if ((int)decoded->altitude) { - jsonObj["payload"]["altitude"] = (int)decoded->altitude; - } - if ((int)decoded->ground_speed) { - jsonObj["payload"]["ground_speed"] = (unsigned int)decoded->ground_speed; - } - if (int(decoded->ground_track)) { - jsonObj["payload"]["ground_track"] = (unsigned int)decoded->ground_track; - } - if (int(decoded->sats_in_view)) { - jsonObj["payload"]["sats_in_view"] = (unsigned int)decoded->sats_in_view; - } - if ((int)decoded->PDOP) { - jsonObj["payload"]["PDOP"] = (int)decoded->PDOP; - } - if ((int)decoded->HDOP) { - jsonObj["payload"]["HDOP"] = (int)decoded->HDOP; - } - if ((int)decoded->VDOP) { - jsonObj["payload"]["VDOP"] = (int)decoded->VDOP; - } - if ((int)decoded->precision_bits) { - jsonObj["payload"]["precision_bits"] = (int)decoded->precision_bits; - } - } else if (shouldLog) { - LOG_ERROR("Error decoding protobuf for position message!\n"); - return ""; - } - break; - } - case meshtastic_PortNum_WAYPOINT_APP: { - msgType = "position"; - meshtastic_Waypoint scratch; - meshtastic_Waypoint *decoded = NULL; - memset(&scratch, 0, sizeof(scratch)); - if (pb_decode_from_bytes(mp->decoded.payload.bytes, mp->decoded.payload.size, &meshtastic_Waypoint_msg, &scratch)) { - decoded = &scratch; - jsonObj["payload"]["id"] = (unsigned int)decoded->id; - jsonObj["payload"]["name"] = decoded->name; - jsonObj["payload"]["description"] = decoded->description; - jsonObj["payload"]["expire"] = (unsigned int)decoded->expire; - jsonObj["payload"]["locked_to"] = (unsigned int)decoded->locked_to; - jsonObj["payload"]["latitude_i"] = (int)decoded->latitude_i; - jsonObj["payload"]["longitude_i"] = (int)decoded->longitude_i; - } else if (shouldLog) { - LOG_ERROR("Error decoding protobuf for position message!\n"); - return ""; - } - break; - } - case meshtastic_PortNum_NEIGHBORINFO_APP: { - msgType = "neighborinfo"; - meshtastic_NeighborInfo scratch; - meshtastic_NeighborInfo *decoded = NULL; - memset(&scratch, 0, sizeof(scratch)); - if (pb_decode_from_bytes(mp->decoded.payload.bytes, mp->decoded.payload.size, &meshtastic_NeighborInfo_msg, - &scratch)) { - decoded = &scratch; - jsonObj["payload"]["node_id"] = (unsigned int)decoded->node_id; - jsonObj["payload"]["node_broadcast_interval_secs"] = (unsigned int)decoded->node_broadcast_interval_secs; - jsonObj["payload"]["last_sent_by_id"] = (unsigned int)decoded->last_sent_by_id; - jsonObj["payload"]["neighbors_count"] = decoded->neighbors_count; - + } + break; + } + case meshtastic_PortNum_TELEMETRY_APP: + { + msgType = "telemetry"; + meshtastic_Telemetry scratch; + meshtastic_Telemetry *decoded = NULL; + memset(&scratch, 0, sizeof(scratch)); + 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) + { + jsonObj["payload"]["battery_level"] = (unsigned int)decoded->variant.device_metrics.battery_level; + jsonObj["payload"]["voltage"] = decoded->variant.device_metrics.voltage; + jsonObj["payload"]["channel_utilization"] = decoded->variant.device_metrics.channel_utilization; + jsonObj["payload"]["air_util_tx"] = decoded->variant.device_metrics.air_util_tx; + jsonObj["payload"]["uptime_seconds"] = (unsigned int)decoded->variant.device_metrics.uptime_seconds; + } + else if (decoded->which_variant == meshtastic_Telemetry_environment_metrics_tag) + { + jsonObj["payload"]["temperature"] = decoded->variant.environment_metrics.temperature; + jsonObj["payload"]["relative_humidity"] = decoded->variant.environment_metrics.relative_humidity; + jsonObj["payload"]["barometric_pressure"] = decoded->variant.environment_metrics.barometric_pressure; + jsonObj["payload"]["gas_resistance"] = decoded->variant.environment_metrics.gas_resistance; + jsonObj["payload"]["voltage"] = decoded->variant.environment_metrics.voltage; + jsonObj["payload"]["current"] = decoded->variant.environment_metrics.current; + jsonObj["payload"]["lux"] = decoded->variant.environment_metrics.lux; + jsonObj["payload"]["white_lux"] = decoded->variant.environment_metrics.white_lux; + jsonObj["payload"]["iaq"] = (uint)decoded->variant.environment_metrics.iaq; + jsonObj["payload"]["wind_speed"] = decoded->variant.environment_metrics.wind_speed; + jsonObj["payload"]["wind_direction"] = (uint)decoded->variant.environment_metrics.wind_direction; + jsonObj["payload"]["wind_gust"] = decoded->variant.environment_metrics.wind_gust; + jsonObj["payload"]["wind_lull"] = decoded->variant.environment_metrics.wind_lull; + } + else if (decoded->which_variant == meshtastic_Telemetry_air_quality_metrics_tag) + { + jsonObj["payload"]["pm10"] = (unsigned int)decoded->variant.air_quality_metrics.pm10_standard; + jsonObj["payload"]["pm25"] = (unsigned int)decoded->variant.air_quality_metrics.pm25_standard; + jsonObj["payload"]["pm100"] = (unsigned int)decoded->variant.air_quality_metrics.pm100_standard; + jsonObj["payload"]["pm10_e"] = (unsigned int)decoded->variant.air_quality_metrics.pm10_environmental; + jsonObj["payload"]["pm25_e"] = (unsigned int)decoded->variant.air_quality_metrics.pm25_environmental; + jsonObj["payload"]["pm100_e"] = (unsigned int)decoded->variant.air_quality_metrics.pm100_environmental; + } + else if (decoded->which_variant == meshtastic_Telemetry_power_metrics_tag) + { + jsonObj["payload"]["voltage_ch1"] = decoded->variant.power_metrics.ch1_voltage; + jsonObj["payload"]["current_ch1"] = decoded->variant.power_metrics.ch1_current; + jsonObj["payload"]["voltage_ch2"] = decoded->variant.power_metrics.ch2_voltage; + jsonObj["payload"]["current_ch2"] = decoded->variant.power_metrics.ch2_current; + jsonObj["payload"]["voltage_ch3"] = decoded->variant.power_metrics.ch3_voltage; + jsonObj["payload"]["current_ch3"] = decoded->variant.power_metrics.ch3_current; + } + } + else if (shouldLog) + { + LOG_ERROR("Error decoding protobuf for telemetry message!\n"); + return ""; + } + break; + } + case meshtastic_PortNum_NODEINFO_APP: + { + msgType = "nodeinfo"; + meshtastic_User scratch; + meshtastic_User *decoded = NULL; + memset(&scratch, 0, sizeof(scratch)); + if (pb_decode_from_bytes(mp->decoded.payload.bytes, mp->decoded.payload.size, &meshtastic_User_msg, &scratch)) + { + decoded = &scratch; + jsonObj["payload"]["id"] = decoded->id; + jsonObj["payload"]["longname"] = decoded->long_name; + jsonObj["payload"]["shortname"] = decoded->short_name; + jsonObj["payload"]["hardware"] = decoded->hw_model; + jsonObj["payload"]["role"] = (int)decoded->role; + } + else if (shouldLog) + { + LOG_ERROR("Error decoding protobuf for nodeinfo message!\n"); + return ""; + } + break; + } + case meshtastic_PortNum_POSITION_APP: + { + msgType = "position"; + meshtastic_Position scratch; + meshtastic_Position *decoded = NULL; + memset(&scratch, 0, sizeof(scratch)); + if (pb_decode_from_bytes(mp->decoded.payload.bytes, mp->decoded.payload.size, &meshtastic_Position_msg, &scratch)) + { + decoded = &scratch; + if ((int)decoded->time) + { + jsonObj["payload"]["time"] = (unsigned int)decoded->time; + } + if ((int)decoded->timestamp) + { + jsonObj["payload"]["timestamp"] = (unsigned int)decoded->timestamp; + } + jsonObj["payload"]["latitude_i"] = (int)decoded->latitude_i; + jsonObj["payload"]["longitude_i"] = (int)decoded->longitude_i; + if ((int)decoded->altitude) + { + jsonObj["payload"]["altitude"] = (int)decoded->altitude; + } + if ((int)decoded->ground_speed) + { + jsonObj["payload"]["ground_speed"] = (unsigned int)decoded->ground_speed; + } + if (int(decoded->ground_track)) + { + jsonObj["payload"]["ground_track"] = (unsigned int)decoded->ground_track; + } + if (int(decoded->sats_in_view)) + { + jsonObj["payload"]["sats_in_view"] = (unsigned int)decoded->sats_in_view; + } + if ((int)decoded->PDOP) + { + jsonObj["payload"]["PDOP"] = (int)decoded->PDOP; + } + if ((int)decoded->HDOP) + { + jsonObj["payload"]["HDOP"] = (int)decoded->HDOP; + } + if ((int)decoded->VDOP) + { + jsonObj["payload"]["VDOP"] = (int)decoded->VDOP; + } + if ((int)decoded->precision_bits) + { + jsonObj["payload"]["precision_bits"] = (int)decoded->precision_bits; + } + } + else if (shouldLog) + { + LOG_ERROR("Error decoding protobuf for position message!\n"); + return ""; + } + break; + } + case meshtastic_PortNum_WAYPOINT_APP: + { + msgType = "position"; + meshtastic_Waypoint scratch; + meshtastic_Waypoint *decoded = NULL; + memset(&scratch, 0, sizeof(scratch)); + if (pb_decode_from_bytes(mp->decoded.payload.bytes, mp->decoded.payload.size, &meshtastic_Waypoint_msg, &scratch)) + { + decoded = &scratch; + jsonObj["payload"]["id"] = (unsigned int)decoded->id; + jsonObj["payload"]["name"] = decoded->name; + jsonObj["payload"]["description"] = decoded->description; + jsonObj["payload"]["expire"] = (unsigned int)decoded->expire; + jsonObj["payload"]["locked_to"] = (unsigned int)decoded->locked_to; + jsonObj["payload"]["latitude_i"] = (int)decoded->latitude_i; + jsonObj["payload"]["longitude_i"] = (int)decoded->longitude_i; + } + else if (shouldLog) + { + LOG_ERROR("Error decoding protobuf for position message!\n"); + return ""; + } + break; + } + case meshtastic_PortNum_NEIGHBORINFO_APP: + { + msgType = "neighborinfo"; + meshtastic_NeighborInfo scratch; + meshtastic_NeighborInfo *decoded = NULL; + memset(&scratch, 0, sizeof(scratch)); + if (pb_decode_from_bytes(mp->decoded.payload.bytes, mp->decoded.payload.size, &meshtastic_NeighborInfo_msg, + &scratch)) + { + decoded = &scratch; + jsonObj["payload"]["node_id"] = (unsigned int)decoded->node_id; + jsonObj["payload"]["node_broadcast_interval_secs"] = (unsigned int)decoded->node_broadcast_interval_secs; + jsonObj["payload"]["last_sent_by_id"] = (unsigned int)decoded->last_sent_by_id; + jsonObj["payload"]["neighbors_count"] = decoded->neighbors_count; + JsonObject neighbors_obj = arrayObj.to(); JsonArray neighbors = neighbors_obj.createNestedArray("neighbors"); JsonObject neighbors_0 = neighbors.createNestedObject(); - for (uint8_t i = 0; i < decoded->neighbors_count; i++) { - neighbors_0["node_id"] = (unsigned int)decoded->neighbors[i].node_id; - neighbors_0["snr"] = (int)decoded->neighbors[i].snr; - neighbors[i+1] = neighbors_0; - neighbors_0.clear(); - } + for (uint8_t i = 0; i < decoded->neighbors_count; i++) + { + neighbors_0["node_id"] = (unsigned int)decoded->neighbors[i].node_id; + neighbors_0["snr"] = (int)decoded->neighbors[i].snr; + neighbors[i + 1] = neighbors_0; + neighbors_0.clear(); + } neighbors.remove(0); jsonObj["payload"]["neighbors"] = neighbors; - } else if (shouldLog) { - LOG_ERROR("Error decoding protobuf for neighborinfo message!\n"); - return ""; - } - break; - } - case meshtastic_PortNum_TRACEROUTE_APP: { - if (mp->decoded.request_id) { // Only report the traceroute response - msgType = "traceroute"; - meshtastic_RouteDiscovery scratch; - meshtastic_RouteDiscovery *decoded = NULL; - memset(&scratch, 0, sizeof(scratch)); - if (pb_decode_from_bytes(mp->decoded.payload.bytes, mp->decoded.payload.size, &meshtastic_RouteDiscovery_msg, - &scratch)) { - decoded = &scratch; - JsonArray route = arrayObj.createNestedArray("route"); - - auto addToRoute = [](JsonArray *route, NodeNum num) { - char long_name[40] = "Unknown"; - meshtastic_NodeInfoLite *node = nodeDB->getMeshNode(num); - bool name_known = node ? node->has_user : false; - if (name_known) - memcpy(long_name, node->user.long_name, sizeof(long_name)); - route->add(long_name); - }; - - addToRoute(&route,mp->to); //route.add(mp->to); - for (uint8_t i = 0; i < decoded->route_count; i++) { - addToRoute(&route,decoded->route[i]); //route.add(decoded->route[i]); - } - addToRoute(&route,mp->from); //route.add(mp->from); // Ended at the original destination (source of response) - - jsonObj["payload"]["route"] = route; - } else if (shouldLog) { - LOG_ERROR("Error decoding protobuf for traceroute message!\n"); - return ""; - } - } else { - LOG_WARN("Traceroute response not reported"); + } + else if (shouldLog) + { + LOG_ERROR("Error decoding protobuf for neighborinfo message!\n"); return ""; } - break; - } - case meshtastic_PortNum_DETECTION_SENSOR_APP: { - msgType = "detection"; - char payloadStr[(mp->decoded.payload.size) + 1]; - memcpy(payloadStr, mp->decoded.payload.bytes, mp->decoded.payload.size); - payloadStr[mp->decoded.payload.size] = 0; // null terminated string - jsonObj["payload"]["text"] = payloadStr; - break; - } - case meshtastic_PortNum_REMOTE_HARDWARE_APP: { - meshtastic_HardwareMessage scratch; - meshtastic_HardwareMessage *decoded = NULL; - memset(&scratch, 0, sizeof(scratch)); - if (pb_decode_from_bytes(mp->decoded.payload.bytes, mp->decoded.payload.size, &meshtastic_HardwareMessage_msg, - &scratch)) { - decoded = &scratch; - if (decoded->type == meshtastic_HardwareMessage_Type_GPIOS_CHANGED) { - msgType = "gpios_changed"; - jsonObj["payload"]["gpio_value"] = (unsigned int)decoded->gpio_value; - } else if (decoded->type == meshtastic_HardwareMessage_Type_READ_GPIOS_REPLY) { - msgType = "gpios_read_reply"; - jsonObj["payload"]["gpio_value"] = (unsigned int)decoded->gpio_value; - jsonObj["payload"]["gpio_mask"] = (unsigned int)decoded->gpio_mask; - } - } else if (shouldLog) { - LOG_ERROR("Error decoding protobuf for RemoteHardware message!\n"); - return ""; - } - break; - } - // add more packet types here if needed - default: - LOG_WARN("Unsupported packet type %d\n",mp->decoded.portnum); + break; + } + case meshtastic_PortNum_TRACEROUTE_APP: + { + if (mp->decoded.request_id) + { // Only report the traceroute response + msgType = "traceroute"; + meshtastic_RouteDiscovery scratch; + meshtastic_RouteDiscovery *decoded = NULL; + memset(&scratch, 0, sizeof(scratch)); + if (pb_decode_from_bytes(mp->decoded.payload.bytes, mp->decoded.payload.size, &meshtastic_RouteDiscovery_msg, + &scratch)) + { + decoded = &scratch; + JsonArray route = arrayObj.createNestedArray("route"); + + auto addToRoute = [](JsonArray *route, NodeNum num) + { + char long_name[40] = "Unknown"; + meshtastic_NodeInfoLite *node = nodeDB->getMeshNode(num); + bool name_known = node ? node->has_user : false; + if (name_known) + memcpy(long_name, node->user.long_name, sizeof(long_name)); + route->add(long_name); + }; + + addToRoute(&route, mp->to); // route.add(mp->to); + for (uint8_t i = 0; i < decoded->route_count; i++) + { + addToRoute(&route, decoded->route[i]); // route.add(decoded->route[i]); + } + addToRoute(&route, mp->from); // route.add(mp->from); // Ended at the original destination (source of response) + + jsonObj["payload"]["route"] = route; + } + else if (shouldLog) + { + LOG_ERROR("Error decoding protobuf for traceroute message!\n"); + return ""; + } + } + else + { + LOG_WARN("Traceroute response not reported"); + return ""; + } + break; + } + case meshtastic_PortNum_DETECTION_SENSOR_APP: + { + msgType = "detection"; + char payloadStr[(mp->decoded.payload.size) + 1]; + memcpy(payloadStr, mp->decoded.payload.bytes, mp->decoded.payload.size); + payloadStr[mp->decoded.payload.size] = 0; // null terminated string + jsonObj["payload"]["text"] = payloadStr; + break; + } + case meshtastic_PortNum_REMOTE_HARDWARE_APP: + { + meshtastic_HardwareMessage scratch; + meshtastic_HardwareMessage *decoded = NULL; + memset(&scratch, 0, sizeof(scratch)); + if (pb_decode_from_bytes(mp->decoded.payload.bytes, mp->decoded.payload.size, &meshtastic_HardwareMessage_msg, + &scratch)) + { + decoded = &scratch; + if (decoded->type == meshtastic_HardwareMessage_Type_GPIOS_CHANGED) + { + msgType = "gpios_changed"; + jsonObj["payload"]["gpio_value"] = (unsigned int)decoded->gpio_value; + } + else if (decoded->type == meshtastic_HardwareMessage_Type_READ_GPIOS_REPLY) + { + msgType = "gpios_read_reply"; + jsonObj["payload"]["gpio_value"] = (unsigned int)decoded->gpio_value; + jsonObj["payload"]["gpio_mask"] = (unsigned int)decoded->gpio_mask; + } + } + else if (shouldLog) + { + LOG_ERROR("Error decoding protobuf for RemoteHardware message!\n"); + return ""; + } + break; + } + // add more packet types here if needed + default: + LOG_WARN("Unsupported packet type %d\n", mp->decoded.portnum); return ""; - break; - } - } else if (shouldLog) { - LOG_WARN("Couldn't convert encrypted payload of MeshPacket to JSON\n"); + break; + } + } + else if (shouldLog) + { + LOG_WARN("Couldn't convert encrypted payload of MeshPacket to JSON\n"); return ""; - } + } - jsonObj["id"] = (unsigned int)mp->id; - jsonObj["timestamp"] = (unsigned int)mp->rx_time; - jsonObj["to"] = (unsigned int)mp->to; - jsonObj["from"] = (unsigned int)mp->from; - jsonObj["channel"] = (unsigned int)mp->channel; - jsonObj["type"] = msgType.c_str(); - jsonObj["sender"] = owner.id; - if (mp->rx_rssi != 0) - jsonObj["rssi"] = (int)mp->rx_rssi; - if (mp->rx_snr != 0) - jsonObj["snr"] = (float)mp->rx_snr; - if (mp->hop_start != 0 && mp->hop_limit <= mp->hop_start) { - jsonObj["hops_away"] = (unsigned int)(mp->hop_start - mp->hop_limit); - jsonObj["hop_start"] = (unsigned int)(mp->hop_start); - } + jsonObj["id"] = (unsigned int)mp->id; + jsonObj["timestamp"] = (unsigned int)mp->rx_time; + jsonObj["to"] = (unsigned int)mp->to; + jsonObj["from"] = (unsigned int)mp->from; + jsonObj["channel"] = (unsigned int)mp->channel; + jsonObj["type"] = msgType.c_str(); + jsonObj["sender"] = owner.id; + if (mp->rx_rssi != 0) + jsonObj["rssi"] = (int)mp->rx_rssi; + if (mp->rx_snr != 0) + jsonObj["snr"] = (float)mp->rx_snr; + if (mp->hop_start != 0 && mp->hop_limit <= mp->hop_start) + { + jsonObj["hops_away"] = (unsigned int)(mp->hop_start - mp->hop_limit); + jsonObj["hop_start"] = (unsigned int)(mp->hop_start); + } - // serialize and write it to the stream + // serialize and write it to the stream // Serial.printf("serialized json message: \r\n"); // serializeJson(jsonObj, Serial); @@ -314,39 +378,40 @@ std::string MeshPacketSerializer::JsonSerialize(const meshtastic_MeshPacket *mp, std::string jsonStr = ""; serializeJson(jsonObj, jsonStr); - if (shouldLog) - LOG_INFO("serialized json message: %s\n", jsonStr.c_str()); + if (shouldLog) + LOG_INFO("serialized json message: %s\n", jsonStr.c_str()); - return jsonStr; + return jsonStr; } std::string MeshPacketSerializer::JsonSerializeEncrypted(const meshtastic_MeshPacket *mp) { jsonObj.clear(); - jsonObj["id"] = (unsigned int)mp->id; - jsonObj["time_ms"] = (double)millis(); - jsonObj["timestamp"] = (unsigned int)mp->rx_time; - jsonObj["to"] = (unsigned int)mp->to; - jsonObj["from"] = (unsigned int)mp->from; - jsonObj["channel"] = (unsigned int)mp->channel; - jsonObj["want_ack"] = mp->want_ack; + jsonObj["id"] = (unsigned int)mp->id; + jsonObj["time_ms"] = (double)millis(); + jsonObj["timestamp"] = (unsigned int)mp->rx_time; + jsonObj["to"] = (unsigned int)mp->to; + jsonObj["from"] = (unsigned int)mp->from; + jsonObj["channel"] = (unsigned int)mp->channel; + jsonObj["want_ack"] = mp->want_ack; - if (mp->rx_rssi != 0) - jsonObj["rssi"] = (int)mp->rx_rssi; - if (mp->rx_snr != 0) - jsonObj["snr"] = (float)mp->rx_snr; - if (mp->hop_start != 0 && mp->hop_limit <= mp->hop_start) { - jsonObj["hops_away"] = (unsigned int)(mp->hop_start - mp->hop_limit); - jsonObj["hop_start"] = (unsigned int)(mp->hop_start); - } - jsonObj["size"] = (unsigned int)mp->encrypted.size; - auto encryptedStr = bytesToHex(mp->encrypted.bytes, mp->encrypted.size); - jsonObj["bytes"] = encryptedStr.c_str(); + if (mp->rx_rssi != 0) + jsonObj["rssi"] = (int)mp->rx_rssi; + if (mp->rx_snr != 0) + jsonObj["snr"] = (float)mp->rx_snr; + if (mp->hop_start != 0 && mp->hop_limit <= mp->hop_start) + { + jsonObj["hops_away"] = (unsigned int)(mp->hop_start - mp->hop_limit); + jsonObj["hop_start"] = (unsigned int)(mp->hop_start); + } + jsonObj["size"] = (unsigned int)mp->encrypted.size; + auto encryptedStr = bytesToHex(mp->encrypted.bytes, mp->encrypted.size); + jsonObj["bytes"] = encryptedStr.c_str(); - // serialize and write it to the stream + // serialize and write it to the stream std::string jsonStr = ""; serializeJson(jsonObj, jsonStr); - return jsonStr; + return jsonStr; } #endif \ No newline at end of file From c4c85777d035402140d96270e280051185e0a218 Mon Sep 17 00:00:00 2001 From: beegee-tokyo Date: Thu, 12 Sep 2024 13:20:09 +0800 Subject: [PATCH 09/88] Another try to get the code format correct. --- src/mqtt/MQTT.cpp | 1097 +++++++++++-------------- src/platform/nrf52/NRF52Bluetooth.cpp | 456 +++++----- 2 files changed, 719 insertions(+), 834 deletions(-) diff --git a/src/mqtt/MQTT.cpp b/src/mqtt/MQTT.cpp index 3e0e692b4..a4921e684 100644 --- a/src/mqtt/MQTT.cpp +++ b/src/mqtt/MQTT.cpp @@ -33,194 +33,161 @@ Allocator &mqttPool = staticMqttPool; void MQTT::mqttCallback(char *topic, byte *payload, unsigned int length) { - mqtt->onReceive(topic, payload, length); + mqtt->onReceive(topic, payload, length); } void MQTT::onClientProxyReceive(meshtastic_MqttClientProxyMessage msg) { - onReceive(msg.topic, msg.payload_variant.data.bytes, msg.payload_variant.data.size); + onReceive(msg.topic, msg.payload_variant.data.bytes, msg.payload_variant.data.size); } void MQTT::onReceive(char *topic, byte *payload, size_t length) { - meshtastic_ServiceEnvelope e = meshtastic_ServiceEnvelope_init_default; + meshtastic_ServiceEnvelope e = meshtastic_ServiceEnvelope_init_default; - if (moduleConfig.mqtt.json_enabled && (strncmp(topic, jsonTopic.c_str(), jsonTopic.length()) == 0)) - { - // check if this is a json payload message by comparing the topic start - char payloadStr[length + 1]; - memcpy(payloadStr, payload, length); - payloadStr[length] = 0; // null terminated string - JSONValue *json_value = JSON::Parse(payloadStr); - if (json_value != NULL) - { - // check if it is a valid envelope - JSONObject json; - json = json_value->AsObject(); + if (moduleConfig.mqtt.json_enabled && (strncmp(topic, jsonTopic.c_str(), jsonTopic.length()) == 0)) { + // check if this is a json payload message by comparing the topic start + char payloadStr[length + 1]; + memcpy(payloadStr, payload, length); + payloadStr[length] = 0; // null terminated string + JSONValue *json_value = JSON::Parse(payloadStr); + if (json_value != NULL) { + // check if it is a valid envelope + JSONObject json; + json = json_value->AsObject(); - // parse the channel name from the topic string - // the topic has been checked above for having jsonTopic prefix, so just move past it - char *ptr = topic + jsonTopic.length(); - ptr = strtok(ptr, "/") ? strtok(ptr, "/") : ptr; // if another "/" was added, parse string up to that character - meshtastic_Channel sendChannel = channels.getByName(ptr); - // We allow downlink JSON packets only on a channel named "mqtt" - if (strncasecmp(channels.getGlobalId(sendChannel.index), Channels::mqttChannel, strlen(Channels::mqttChannel)) == 0 && - sendChannel.settings.downlink_enabled) - { - if (isValidJsonEnvelope(json)) - { - // this is a valid envelope - if (json["type"]->AsString().compare("sendtext") == 0 && json["payload"]->IsString()) - { - std::string jsonPayloadStr = json["payload"]->AsString(); - LOG_INFO("JSON payload %s, length %u\n", jsonPayloadStr.c_str(), jsonPayloadStr.length()); + // parse the channel name from the topic string + // the topic has been checked above for having jsonTopic prefix, so just move past it + char *ptr = topic + jsonTopic.length(); + ptr = strtok(ptr, "/") ? strtok(ptr, "/") : ptr; // if another "/" was added, parse string up to that character + meshtastic_Channel sendChannel = channels.getByName(ptr); + // We allow downlink JSON packets only on a channel named "mqtt" + if (strncasecmp(channels.getGlobalId(sendChannel.index), Channels::mqttChannel, strlen(Channels::mqttChannel)) == 0 && + sendChannel.settings.downlink_enabled) { + if (isValidJsonEnvelope(json)) { + // this is a valid envelope + if (json["type"]->AsString().compare("sendtext") == 0 && json["payload"]->IsString()) { + std::string jsonPayloadStr = json["payload"]->AsString(); + LOG_INFO("JSON payload %s, length %u\n", jsonPayloadStr.c_str(), jsonPayloadStr.length()); - // construct protobuf data packet using TEXT_MESSAGE, send it to the mesh - meshtastic_MeshPacket *p = router->allocForSending(); - p->decoded.portnum = meshtastic_PortNum_TEXT_MESSAGE_APP; - if (json.find("channel") != json.end() && json["channel"]->IsNumber() && - (json["channel"]->AsNumber() < channels.getNumChannels())) - p->channel = json["channel"]->AsNumber(); - if (json.find("to") != json.end() && json["to"]->IsNumber()) - p->to = json["to"]->AsNumber(); - if (json.find("hopLimit") != json.end() && json["hopLimit"]->IsNumber()) - p->hop_limit = json["hopLimit"]->AsNumber(); - if (jsonPayloadStr.length() <= sizeof(p->decoded.payload.bytes)) - { - memcpy(p->decoded.payload.bytes, jsonPayloadStr.c_str(), jsonPayloadStr.length()); - p->decoded.payload.size = jsonPayloadStr.length(); - service->sendToMesh(p, RX_SRC_LOCAL); - } - else - { - LOG_WARN("Received MQTT json payload too long, dropping\n"); - } - } - else if (json["type"]->AsString().compare("sendposition") == 0 && json["payload"]->IsObject()) - { - // invent the "sendposition" type for a valid envelope - JSONObject posit; - posit = json["payload"]->AsObject(); // get nested JSON Position - meshtastic_Position pos = meshtastic_Position_init_default; - if (posit.find("latitude_i") != posit.end() && posit["latitude_i"]->IsNumber()) - pos.latitude_i = posit["latitude_i"]->AsNumber(); - if (posit.find("longitude_i") != posit.end() && posit["longitude_i"]->IsNumber()) - pos.longitude_i = posit["longitude_i"]->AsNumber(); - if (posit.find("altitude") != posit.end() && posit["altitude"]->IsNumber()) - pos.altitude = posit["altitude"]->AsNumber(); - if (posit.find("time") != posit.end() && posit["time"]->IsNumber()) - pos.time = posit["time"]->AsNumber(); + // construct protobuf data packet using TEXT_MESSAGE, send it to the mesh + meshtastic_MeshPacket *p = router->allocForSending(); + p->decoded.portnum = meshtastic_PortNum_TEXT_MESSAGE_APP; + if (json.find("channel") != json.end() && json["channel"]->IsNumber() && + (json["channel"]->AsNumber() < channels.getNumChannels())) + p->channel = json["channel"]->AsNumber(); + if (json.find("to") != json.end() && json["to"]->IsNumber()) + p->to = json["to"]->AsNumber(); + if (json.find("hopLimit") != json.end() && json["hopLimit"]->IsNumber()) + p->hop_limit = json["hopLimit"]->AsNumber(); + if (jsonPayloadStr.length() <= sizeof(p->decoded.payload.bytes)) { + memcpy(p->decoded.payload.bytes, jsonPayloadStr.c_str(), jsonPayloadStr.length()); + p->decoded.payload.size = jsonPayloadStr.length(); + service->sendToMesh(p, RX_SRC_LOCAL); + } else { + LOG_WARN("Received MQTT json payload too long, dropping\n"); + } + } else if (json["type"]->AsString().compare("sendposition") == 0 && json["payload"]->IsObject()) { + // invent the "sendposition" type for a valid envelope + JSONObject posit; + posit = json["payload"]->AsObject(); // get nested JSON Position + meshtastic_Position pos = meshtastic_Position_init_default; + if (posit.find("latitude_i") != posit.end() && posit["latitude_i"]->IsNumber()) + pos.latitude_i = posit["latitude_i"]->AsNumber(); + if (posit.find("longitude_i") != posit.end() && posit["longitude_i"]->IsNumber()) + pos.longitude_i = posit["longitude_i"]->AsNumber(); + if (posit.find("altitude") != posit.end() && posit["altitude"]->IsNumber()) + pos.altitude = posit["altitude"]->AsNumber(); + if (posit.find("time") != posit.end() && posit["time"]->IsNumber()) + pos.time = posit["time"]->AsNumber(); - // construct protobuf data packet using POSITION, send it to the mesh - meshtastic_MeshPacket *p = router->allocForSending(); - p->decoded.portnum = meshtastic_PortNum_POSITION_APP; - if (json.find("channel") != json.end() && json["channel"]->IsNumber() && - (json["channel"]->AsNumber() < channels.getNumChannels())) - p->channel = json["channel"]->AsNumber(); - if (json.find("to") != json.end() && json["to"]->IsNumber()) - p->to = json["to"]->AsNumber(); - if (json.find("hopLimit") != json.end() && json["hopLimit"]->IsNumber()) - p->hop_limit = json["hopLimit"]->AsNumber(); - p->decoded.payload.size = - pb_encode_to_bytes(p->decoded.payload.bytes, sizeof(p->decoded.payload.bytes), - &meshtastic_Position_msg, &pos); // make the Data protobuf from position - service->sendToMesh(p, RX_SRC_LOCAL); - } - else - { - LOG_DEBUG("JSON Ignoring downlink message with unsupported type.\n"); - } - } - else - { - LOG_ERROR("JSON Received payload on MQTT but not a valid envelope.\n"); - } - } - else - { - LOG_WARN("JSON downlink received on channel not called 'mqtt' or without downlink enabled.\n"); - } - } - else - { - // no json, this is an invalid payload - LOG_ERROR("JSON Received payload on MQTT but not a valid JSON\n"); - } - delete json_value; - } - else - { - if (length == 0) - { - LOG_WARN("Empty MQTT payload received, topic %s!\n", topic); - return; - } - else if (!pb_decode_from_bytes(payload, length, &meshtastic_ServiceEnvelope_msg, &e)) - { - LOG_ERROR("Invalid MQTT service envelope, topic %s, len %u!\n", topic, length); - return; - } - else - { - if (e.channel_id == NULL || e.gateway_id == NULL) - { - LOG_ERROR("Invalid MQTT service envelope, topic %s, len %u!\n", topic, length); - return; - } - meshtastic_Channel ch = channels.getByName(e.channel_id); - if (strcmp(e.gateway_id, owner.id) == 0) - { - // Generate an implicit ACK towards ourselves (handled and processed only locally!) for this message. - // We do this because packets are not rebroadcasted back into MQTT anymore and we assume that at least one node - // receives it when we get our own packet back. Then we'll stop our retransmissions. - if (e.packet && getFrom(e.packet) == nodeDB->getNodeNum()) - routingModule->sendAckNak(meshtastic_Routing_Error_NONE, getFrom(e.packet), e.packet->id, ch.index); - else - LOG_INFO("Ignoring downlink message we originally sent.\n"); - } - else - { - // Find channel by channel_id and check downlink_enabled - if ((strcmp(e.channel_id, "PKI") == 0 && e.packet) || - (strcmp(e.channel_id, channels.getGlobalId(ch.index)) == 0 && e.packet && ch.settings.downlink_enabled)) - { - LOG_INFO("Received MQTT topic %s, len=%u\n", topic, length); - meshtastic_MeshPacket *p = packetPool.allocCopy(*e.packet); - p->via_mqtt = true; // Mark that the packet was received via MQTT + // construct protobuf data packet using POSITION, send it to the mesh + meshtastic_MeshPacket *p = router->allocForSending(); + p->decoded.portnum = meshtastic_PortNum_POSITION_APP; + if (json.find("channel") != json.end() && json["channel"]->IsNumber() && + (json["channel"]->AsNumber() < channels.getNumChannels())) + p->channel = json["channel"]->AsNumber(); + if (json.find("to") != json.end() && json["to"]->IsNumber()) + p->to = json["to"]->AsNumber(); + if (json.find("hopLimit") != json.end() && json["hopLimit"]->IsNumber()) + p->hop_limit = json["hopLimit"]->AsNumber(); + p->decoded.payload.size = + pb_encode_to_bytes(p->decoded.payload.bytes, sizeof(p->decoded.payload.bytes), + &meshtastic_Position_msg, &pos); // make the Data protobuf from position + service->sendToMesh(p, RX_SRC_LOCAL); + } else { + LOG_DEBUG("JSON Ignoring downlink message with unsupported type.\n"); + } + } else { + LOG_ERROR("JSON Received payload on MQTT but not a valid envelope.\n"); + } + } else { + LOG_WARN("JSON downlink received on channel not called 'mqtt' or without downlink enabled.\n"); + } + } else { + // no json, this is an invalid payload + LOG_ERROR("JSON Received payload on MQTT but not a valid JSON\n"); + } + delete json_value; + } else { + if (length == 0) { + LOG_WARN("Empty MQTT payload received, topic %s!\n", topic); + return; + } else if (!pb_decode_from_bytes(payload, length, &meshtastic_ServiceEnvelope_msg, &e)) { + LOG_ERROR("Invalid MQTT service envelope, topic %s, len %u!\n", topic, length); + return; + } else { + if (e.channel_id == NULL || e.gateway_id == NULL) { + LOG_ERROR("Invalid MQTT service envelope, topic %s, len %u!\n", topic, length); + return; + } + meshtastic_Channel ch = channels.getByName(e.channel_id); + if (strcmp(e.gateway_id, owner.id) == 0) { + // Generate an implicit ACK towards ourselves (handled and processed only locally!) for this message. + // We do this because packets are not rebroadcasted back into MQTT anymore and we assume that at least one node + // receives it when we get our own packet back. Then we'll stop our retransmissions. + if (e.packet && getFrom(e.packet) == nodeDB->getNodeNum()) + routingModule->sendAckNak(meshtastic_Routing_Error_NONE, getFrom(e.packet), e.packet->id, ch.index); + else + LOG_INFO("Ignoring downlink message we originally sent.\n"); + } else { + // Find channel by channel_id and check downlink_enabled + if ((strcmp(e.channel_id, "PKI") == 0 && e.packet) || + (strcmp(e.channel_id, channels.getGlobalId(ch.index)) == 0 && e.packet && ch.settings.downlink_enabled)) { + LOG_INFO("Received MQTT topic %s, len=%u\n", topic, length); + meshtastic_MeshPacket *p = packetPool.allocCopy(*e.packet); + p->via_mqtt = true; // Mark that the packet was received via MQTT - if (p->which_payload_variant == meshtastic_MeshPacket_decoded_tag) - { - p->channel = ch.index; - } + if (p->which_payload_variant == meshtastic_MeshPacket_decoded_tag) { + p->channel = ch.index; + } - // PKI messages get accepted even if we can't decrypt - if (router && p->which_payload_variant == meshtastic_MeshPacket_encrypted_tag && - strcmp(e.channel_id, "PKI") == 0) - { - meshtastic_NodeInfoLite *tx = nodeDB->getMeshNode(getFrom(p)); - meshtastic_NodeInfoLite *rx = nodeDB->getMeshNode(p->to); - // Only accept PKI messages to us, or if we have both the sender and receiver in our nodeDB, as then it's - // likely they discovered each other via a channel we have downlink enabled for - if (p->to == nodeDB->getNodeNum() || (tx && tx->has_user && rx && rx->has_user)) - router->enqueueReceivedMessage(p); - } - else if (router && perhapsDecode(p)) // ignore messages if we don't have the channel key - router->enqueueReceivedMessage(p); - else - packetPool.release(p); - } - } - } - // make sure to free both strings and the MeshPacket (passing in NULL is acceptable) - free(e.channel_id); - free(e.gateway_id); - free(e.packet); - } + // PKI messages get accepted even if we can't decrypt + if (router && p->which_payload_variant == meshtastic_MeshPacket_encrypted_tag && + strcmp(e.channel_id, "PKI") == 0) { + meshtastic_NodeInfoLite *tx = nodeDB->getMeshNode(getFrom(p)); + meshtastic_NodeInfoLite *rx = nodeDB->getMeshNode(p->to); + // Only accept PKI messages to us, or if we have both the sender and receiver in our nodeDB, as then it's + // likely they discovered each other via a channel we have downlink enabled for + if (p->to == nodeDB->getNodeNum() || (tx && tx->has_user && rx && rx->has_user)) + router->enqueueReceivedMessage(p); + } else if (router && perhapsDecode(p)) // ignore messages if we don't have the channel key + router->enqueueReceivedMessage(p); + else + packetPool.release(p); + } + } + } + // make sure to free both strings and the MeshPacket (passing in NULL is acceptable) + free(e.channel_id); + free(e.gateway_id); + free(e.packet); + } } void mqttInit() { - new MQTT(); + new MQTT(); } #if HAS_NETWORKING @@ -229,551 +196,483 @@ MQTT::MQTT() : concurrency::OSThread("mqtt"), pubSub(mqttClient), mqttQueue(MAX_ MQTT::MQTT() : concurrency::OSThread("mqtt"), mqttQueue(MAX_MQTT_QUEUE) #endif { - if (moduleConfig.mqtt.enabled) - { - LOG_DEBUG("Initializing MQTT\n"); + if (moduleConfig.mqtt.enabled) { + LOG_DEBUG("Initializing MQTT\n"); - assert(!mqtt); - mqtt = this; + assert(!mqtt); + mqtt = this; - if (*moduleConfig.mqtt.root) - { - cryptTopic = moduleConfig.mqtt.root + cryptTopic; - jsonTopic = moduleConfig.mqtt.root + jsonTopic; - mapTopic = moduleConfig.mqtt.root + mapTopic; - } - else - { - cryptTopic = "msh" + cryptTopic; - jsonTopic = "msh" + jsonTopic; - mapTopic = "msh" + mapTopic; - } + if (*moduleConfig.mqtt.root) { + cryptTopic = moduleConfig.mqtt.root + cryptTopic; + jsonTopic = moduleConfig.mqtt.root + jsonTopic; + mapTopic = moduleConfig.mqtt.root + mapTopic; + } else { + cryptTopic = "msh" + cryptTopic; + jsonTopic = "msh" + jsonTopic; + mapTopic = "msh" + mapTopic; + } - if (moduleConfig.mqtt.map_reporting_enabled && moduleConfig.mqtt.has_map_report_settings) - { - map_position_precision = Default::getConfiguredOrDefault(moduleConfig.mqtt.map_report_settings.position_precision, - default_map_position_precision); - map_publish_interval_msecs = Default::getConfiguredOrDefaultMs( - moduleConfig.mqtt.map_report_settings.publish_interval_secs, default_map_publish_interval_secs); - } + if (moduleConfig.mqtt.map_reporting_enabled && moduleConfig.mqtt.has_map_report_settings) { + map_position_precision = Default::getConfiguredOrDefault(moduleConfig.mqtt.map_report_settings.position_precision, + default_map_position_precision); + map_publish_interval_msecs = Default::getConfiguredOrDefaultMs( + moduleConfig.mqtt.map_report_settings.publish_interval_secs, default_map_publish_interval_secs); + } #if HAS_NETWORKING - if (!moduleConfig.mqtt.proxy_to_client_enabled) - pubSub.setCallback(mqttCallback); + if (!moduleConfig.mqtt.proxy_to_client_enabled) + pubSub.setCallback(mqttCallback); #endif - if (moduleConfig.mqtt.proxy_to_client_enabled) - { - LOG_INFO("MQTT configured to use client proxy...\n"); - enabled = true; - runASAP = true; - reconnectCount = 0; - publishNodeInfo(); - } - // preflightSleepObserver.observe(&preflightSleep); - } - else - { - disable(); - } + if (moduleConfig.mqtt.proxy_to_client_enabled) { + LOG_INFO("MQTT configured to use client proxy...\n"); + enabled = true; + runASAP = true; + reconnectCount = 0; + publishNodeInfo(); + } + // preflightSleepObserver.observe(&preflightSleep); + } else { + disable(); + } } bool MQTT::isConnectedDirectly() { #if HAS_NETWORKING - return pubSub.connected(); + return pubSub.connected(); #else - return false; + return false; #endif } bool MQTT::publish(const char *topic, const char *payload, bool retained) { - if (moduleConfig.mqtt.proxy_to_client_enabled) - { - meshtastic_MqttClientProxyMessage *msg = mqttClientProxyMessagePool.allocZeroed(); - msg->which_payload_variant = meshtastic_MqttClientProxyMessage_text_tag; - strcpy(msg->topic, topic); - strcpy(msg->payload_variant.text, payload); - msg->retained = retained; - service->sendMqttMessageToClientProxy(msg); - return true; - } + if (moduleConfig.mqtt.proxy_to_client_enabled) { + meshtastic_MqttClientProxyMessage *msg = mqttClientProxyMessagePool.allocZeroed(); + msg->which_payload_variant = meshtastic_MqttClientProxyMessage_text_tag; + strcpy(msg->topic, topic); + strcpy(msg->payload_variant.text, payload); + msg->retained = retained; + service->sendMqttMessageToClientProxy(msg); + return true; + } #if HAS_NETWORKING - else if (isConnectedDirectly()) - { - return pubSub.publish(topic, payload, retained); - } + else if (isConnectedDirectly()) { + return pubSub.publish(topic, payload, retained); + } #endif - return false; + return false; } bool MQTT::publish(const char *topic, const uint8_t *payload, size_t length, bool retained) { - if (moduleConfig.mqtt.proxy_to_client_enabled) - { - meshtastic_MqttClientProxyMessage *msg = mqttClientProxyMessagePool.allocZeroed(); - msg->which_payload_variant = meshtastic_MqttClientProxyMessage_data_tag; - strcpy(msg->topic, topic); - msg->payload_variant.data.size = length; - memcpy(msg->payload_variant.data.bytes, payload, length); - msg->retained = retained; - service->sendMqttMessageToClientProxy(msg); - return true; - } + if (moduleConfig.mqtt.proxy_to_client_enabled) { + meshtastic_MqttClientProxyMessage *msg = mqttClientProxyMessagePool.allocZeroed(); + msg->which_payload_variant = meshtastic_MqttClientProxyMessage_data_tag; + strcpy(msg->topic, topic); + msg->payload_variant.data.size = length; + memcpy(msg->payload_variant.data.bytes, payload, length); + msg->retained = retained; + service->sendMqttMessageToClientProxy(msg); + return true; + } #if HAS_NETWORKING - else if (isConnectedDirectly()) - { - return pubSub.publish(topic, payload, length, retained); - } + else if (isConnectedDirectly()) { + return pubSub.publish(topic, payload, length, retained); + } #endif - return false; + return false; } void MQTT::reconnect() { - if (wantsLink()) - { - if (moduleConfig.mqtt.proxy_to_client_enabled) - { - LOG_INFO("MQTT connecting via client proxy instead...\n"); - enabled = true; - runASAP = true; - reconnectCount = 0; + if (wantsLink()) { + if (moduleConfig.mqtt.proxy_to_client_enabled) { + LOG_INFO("MQTT connecting via client proxy instead...\n"); + enabled = true; + runASAP = true; + reconnectCount = 0; - publishNodeInfo(); - return; // Don't try to connect directly to the server - } + publishNodeInfo(); + return; // Don't try to connect directly to the server + } #if HAS_NETWORKING - // Defaults - int serverPort = 1883; - const char *serverAddr = default_mqtt_address; - const char *mqttUsername = default_mqtt_username; - const char *mqttPassword = default_mqtt_password; + // Defaults + int serverPort = 1883; + const char *serverAddr = default_mqtt_address; + const char *mqttUsername = default_mqtt_username; + const char *mqttPassword = default_mqtt_password; - if (*moduleConfig.mqtt.address) - { - serverAddr = moduleConfig.mqtt.address; - mqttUsername = moduleConfig.mqtt.username; - mqttPassword = moduleConfig.mqtt.password; - } + if (*moduleConfig.mqtt.address) { + serverAddr = moduleConfig.mqtt.address; + mqttUsername = moduleConfig.mqtt.username; + mqttPassword = moduleConfig.mqtt.password; + } #if HAS_WIFI && !defined(ARCH_PORTDUINO) - if (moduleConfig.mqtt.tls_enabled) - { - // change default for encrypted to 8883 - try - { - serverPort = 8883; - wifiSecureClient.setInsecure(); + if (moduleConfig.mqtt.tls_enabled) { + // change default for encrypted to 8883 + try { + serverPort = 8883; + wifiSecureClient.setInsecure(); - pubSub.setClient(wifiSecureClient); - LOG_INFO("Using TLS-encrypted session\n"); - } - catch (const std::exception &e) - { - LOG_ERROR("MQTT ERROR: %s\n", e.what()); - } - } - else - { - LOG_INFO("Using non-TLS-encrypted session\n"); - pubSub.setClient(mqttClient); - } + pubSub.setClient(wifiSecureClient); + LOG_INFO("Using TLS-encrypted session\n"); + } catch (const std::exception &e) { + LOG_ERROR("MQTT ERROR: %s\n", e.what()); + } + } else { + LOG_INFO("Using non-TLS-encrypted session\n"); + pubSub.setClient(mqttClient); + } #elif HAS_NETWORKING - pubSub.setClient(mqttClient); + pubSub.setClient(mqttClient); #endif - String server = String(serverAddr); - int delimIndex = server.indexOf(':'); - if (delimIndex > 0) - { - String port = server.substring(delimIndex + 1, server.length()); - server[delimIndex] = 0; - serverPort = port.toInt(); - serverAddr = server.c_str(); - } - pubSub.setServer(serverAddr, serverPort); - pubSub.setBufferSize(512); + String server = String(serverAddr); + int delimIndex = server.indexOf(':'); + if (delimIndex > 0) { + String port = server.substring(delimIndex + 1, server.length()); + server[delimIndex] = 0; + serverPort = port.toInt(); + serverAddr = server.c_str(); + } + pubSub.setServer(serverAddr, serverPort); + pubSub.setBufferSize(512); - LOG_INFO("Attempting to connect directly to MQTT server %s, port: %d, username: %s, password: %s\n", serverAddr, - serverPort, mqttUsername, mqttPassword); + LOG_INFO("Attempting to connect directly to MQTT server %s, port: %d, username: %s, password: %s\n", serverAddr, + serverPort, mqttUsername, mqttPassword); - bool connected = pubSub.connect(owner.id, mqttUsername, mqttPassword); - if (connected) - { - LOG_INFO("MQTT connected\n"); - enabled = true; // Start running background process again - runASAP = true; - reconnectCount = 0; + bool connected = pubSub.connect(owner.id, mqttUsername, mqttPassword); + if (connected) { + LOG_INFO("MQTT connected\n"); + enabled = true; // Start running background process again + runASAP = true; + reconnectCount = 0; - publishNodeInfo(); - sendSubscriptions(); - } - else - { + publishNodeInfo(); + sendSubscriptions(); + } else { #if HAS_WIFI && !defined(ARCH_PORTDUINO) - reconnectCount++; - LOG_ERROR("Failed to contact MQTT server directly (%d/%d)...\n", reconnectCount, reconnectMax); - if (reconnectCount >= reconnectMax) - { - needReconnect = true; - wifiReconnect->setIntervalFromNow(0); - reconnectCount = 0; - } + reconnectCount++; + LOG_ERROR("Failed to contact MQTT server directly (%d/%d)...\n", reconnectCount, reconnectMax); + if (reconnectCount >= reconnectMax) { + needReconnect = true; + wifiReconnect->setIntervalFromNow(0); + reconnectCount = 0; + } #endif - } + } #endif - } + } } void MQTT::sendSubscriptions() { #if HAS_NETWORKING - bool hasDownlink = false; - size_t numChan = channels.getNumChannels(); - for (size_t i = 0; i < numChan; i++) - { - const auto &ch = channels.getByIndex(i); - if (ch.settings.downlink_enabled) - { - hasDownlink = true; - std::string topic = cryptTopic + channels.getGlobalId(i) + "/+"; - LOG_INFO("Subscribing to %s\n", topic.c_str()); - pubSub.subscribe(topic.c_str(), 1); // FIXME, is QOS 1 right? + bool hasDownlink = false; + size_t numChan = channels.getNumChannels(); + for (size_t i = 0; i < numChan; i++) { + const auto &ch = channels.getByIndex(i); + if (ch.settings.downlink_enabled) { + hasDownlink = true; + std::string topic = cryptTopic + channels.getGlobalId(i) + "/+"; + LOG_INFO("Subscribing to %s\n", topic.c_str()); + pubSub.subscribe(topic.c_str(), 1); // FIXME, is QOS 1 right? #if !defined(ARCH_NRF52) || defined(NRF52_USE_JSON) // JSON is not supported on nRF52, see issue #2804 ### Fixed by using ArduinoJSON ### - if (moduleConfig.mqtt.json_enabled == true) - { - std::string topicDecoded = jsonTopic + channels.getGlobalId(i) + "/+"; - LOG_INFO("Subscribing to %s\n", topicDecoded.c_str()); - pubSub.subscribe(topicDecoded.c_str(), 1); // FIXME, is QOS 1 right? - } + if (moduleConfig.mqtt.json_enabled == true) { + std::string topicDecoded = jsonTopic + channels.getGlobalId(i) + "/+"; + LOG_INFO("Subscribing to %s\n", topicDecoded.c_str()); + pubSub.subscribe(topicDecoded.c_str(), 1); // FIXME, is QOS 1 right? + } #endif // ARCH_NRF52 NRF52_USE_JSON - } - } + } + } #if !MESHTASTIC_EXCLUDE_PKI - if (hasDownlink) - { - std::string topic = cryptTopic + "PKI/+"; - LOG_INFO("Subscribing to %s\n", topic.c_str()); - pubSub.subscribe(topic.c_str(), 1); - } + if (hasDownlink) { + std::string topic = cryptTopic + "PKI/+"; + LOG_INFO("Subscribing to %s\n", topic.c_str()); + pubSub.subscribe(topic.c_str(), 1); + } #endif #endif } bool MQTT::wantsLink() const { - bool hasChannelorMapReport = - moduleConfig.mqtt.enabled && (moduleConfig.mqtt.map_reporting_enabled || channels.anyMqttEnabled()); + bool hasChannelorMapReport = + moduleConfig.mqtt.enabled && (moduleConfig.mqtt.map_reporting_enabled || channels.anyMqttEnabled()); - if (hasChannelorMapReport && moduleConfig.mqtt.proxy_to_client_enabled) - return true; + if (hasChannelorMapReport && moduleConfig.mqtt.proxy_to_client_enabled) + return true; #if HAS_WIFI - return hasChannelorMapReport && WiFi.isConnected(); + return hasChannelorMapReport && WiFi.isConnected(); #endif #if HAS_ETHERNET - return hasChannelorMapReport && Ethernet.linkStatus() == LinkON; + return hasChannelorMapReport && Ethernet.linkStatus() == LinkON; #endif - return false; + return false; } int32_t MQTT::runOnce() { #if HAS_NETWORKING - if (!moduleConfig.mqtt.enabled || !(moduleConfig.mqtt.map_reporting_enabled || channels.anyMqttEnabled())) - return disable(); + if (!moduleConfig.mqtt.enabled || !(moduleConfig.mqtt.map_reporting_enabled || channels.anyMqttEnabled())) + return disable(); - bool wantConnection = wantsLink(); + bool wantConnection = wantsLink(); - perhapsReportToMap(); + perhapsReportToMap(); - // If connected poll rapidly, otherwise only occasionally check for a wifi connection change and ability to contact server - if (moduleConfig.mqtt.proxy_to_client_enabled) - { - publishQueuedMessages(); - return 200; - } - else if (!pubSub.loop()) - { - if (!wantConnection) - return 5000; // If we don't want connection now, check again in 5 secs - else - { - reconnect(); - // If we succeeded, empty the queue one by one and start reading rapidly, else try again in 30 seconds (TCP - // connections are EXPENSIVE so try rarely) - if (isConnectedDirectly()) - { - publishQueuedMessages(); - return 200; - } - else - return 30000; - } - } - else - { - // we are connected to server, check often for new requests on the TCP port - if (!wantConnection) - { - LOG_INFO("MQTT link not needed, dropping\n"); - pubSub.disconnect(); - } + // If connected poll rapidly, otherwise only occasionally check for a wifi connection change and ability to contact server + if (moduleConfig.mqtt.proxy_to_client_enabled) { + publishQueuedMessages(); + return 200; + } - powerFSM.trigger(EVENT_CONTACT_FROM_PHONE); // Suppress entering light sleep (because that would turn off bluetooth) - return 20; - } + else if (!pubSub.loop()) { + if (!wantConnection) + return 5000; // If we don't want connection now, check again in 5 secs + else { + reconnect(); + // If we succeeded, empty the queue one by one and start reading rapidly, else try again in 30 seconds (TCP + // connections are EXPENSIVE so try rarely) + if (isConnectedDirectly()) { + publishQueuedMessages(); + return 200; + } else + return 30000; + } + } else { + // we are connected to server, check often for new requests on the TCP port + if (!wantConnection) { + LOG_INFO("MQTT link not needed, dropping\n"); + pubSub.disconnect(); + } + + powerFSM.trigger(EVENT_CONTACT_FROM_PHONE); // Suppress entering light sleep (because that would turn off bluetooth) + return 20; + } #endif - return 30000; + return 30000; } void MQTT::publishNodeInfo() { - // TODO: NodeInfo broadcast over MQTT only (NODENUM_BROADCAST_NO_LORA) + // TODO: NodeInfo broadcast over MQTT only (NODENUM_BROADCAST_NO_LORA) } void MQTT::publishQueuedMessages() { - if (!mqttQueue.isEmpty()) - { - LOG_DEBUG("Publishing enqueued MQTT message\n"); - // FIXME - this size calculation is super sloppy, but it will go away once we dynamically alloc meshpackets - meshtastic_ServiceEnvelope *env = mqttQueue.dequeuePtr(0); - static uint8_t bytes[meshtastic_MeshPacket_size + 64]; - size_t numBytes = pb_encode_to_bytes(bytes, sizeof(bytes), &meshtastic_ServiceEnvelope_msg, env); - std::string topic; - if (env->packet->pki_encrypted) - { - topic = cryptTopic + "PKI/" + owner.id; - } - else - { - topic = cryptTopic + env->channel_id + "/" + owner.id; - } - LOG_INFO("publish %s, %u bytes from queue\n", topic.c_str(), numBytes); + if (!mqttQueue.isEmpty()) { + LOG_DEBUG("Publishing enqueued MQTT message\n"); + // FIXME - this size calculation is super sloppy, but it will go away once we dynamically alloc meshpackets + meshtastic_ServiceEnvelope *env = mqttQueue.dequeuePtr(0); + static uint8_t bytes[meshtastic_MeshPacket_size + 64]; + size_t numBytes = pb_encode_to_bytes(bytes, sizeof(bytes), &meshtastic_ServiceEnvelope_msg, env); + std::string topic; + if (env->packet->pki_encrypted) { + topic = cryptTopic + "PKI/" + owner.id; + } else { + topic = cryptTopic + env->channel_id + "/" + owner.id; + } + LOG_INFO("publish %s, %u bytes from queue\n", topic.c_str(), numBytes); - publish(topic.c_str(), bytes, numBytes, false); + publish(topic.c_str(), bytes, numBytes, false); #if !defined(ARCH_NRF52) || defined(NRF52_USE_JSON) // JSON is not supported on nRF52, see issue #2804 ### Fixed by using ArduinoJson ### - if (moduleConfig.mqtt.json_enabled) - { - // handle json topic - auto jsonString = MeshPacketSerializer::JsonSerialize(env->packet); - if (jsonString.length() != 0) - { - std::string topicJson; - if (env->packet->pki_encrypted) - { - topicJson = jsonTopic + "PKI/" + owner.id; - } - else - { - topicJson = jsonTopic + env->channel_id + "/" + owner.id; - } - LOG_INFO("JSON publish message to %s, %u bytes: %s\n", topicJson.c_str(), jsonString.length(), - jsonString.c_str()); - publish(topicJson.c_str(), jsonString.c_str(), false); - } - } + if (moduleConfig.mqtt.json_enabled) { + // handle json topic + auto jsonString = MeshPacketSerializer::JsonSerialize(env->packet); + if (jsonString.length() != 0) { + std::string topicJson; + if (env->packet->pki_encrypted) { + topicJson = jsonTopic + "PKI/" + owner.id; + } else { + topicJson = jsonTopic + env->channel_id + "/" + owner.id; + } + LOG_INFO("JSON publish message to %s, %u bytes: %s\n", topicJson.c_str(), jsonString.length(), + jsonString.c_str()); + publish(topicJson.c_str(), jsonString.c_str(), false); + } + } #endif // ARCH_NRF52 NRF52_USE_JSON - mqttPool.release(env); - } + mqttPool.release(env); + } } void MQTT::onSend(const meshtastic_MeshPacket &mp, const meshtastic_MeshPacket &mp_decoded, ChannelIndex chIndex) { - if (mp.via_mqtt) - return; // Don't send messages that came from MQTT back into MQTT - bool uplinkEnabled = false; - for (int i = 0; i <= 7; i++) - { - if (channels.getByIndex(i).settings.uplink_enabled) - uplinkEnabled = true; - } - if (!uplinkEnabled) - return; // no channels have an uplink enabled - auto &ch = channels.getByIndex(chIndex); + if (mp.via_mqtt) + return; // Don't send messages that came from MQTT back into MQTT + bool uplinkEnabled = false; + for (int i = 0; i <= 7; i++) { + if (channels.getByIndex(i).settings.uplink_enabled) + uplinkEnabled = true; + } + if (!uplinkEnabled) + return; // no channels have an uplink enabled + auto &ch = channels.getByIndex(chIndex); - if (!mp.pki_encrypted) - { - if (mp_decoded.which_payload_variant != meshtastic_MeshPacket_decoded_tag) - { - LOG_CRIT("MQTT::onSend(): mp_decoded isn't actually decoded\n"); - return; - } + if (!mp.pki_encrypted) { + if (mp_decoded.which_payload_variant != meshtastic_MeshPacket_decoded_tag) { + LOG_CRIT("MQTT::onSend(): mp_decoded isn't actually decoded\n"); + return; + } - // check for the lowest bit of the data bitfield set false, and the use of one of the default keys. - if (mp_decoded.from != nodeDB->getNodeNum() && mp_decoded.decoded.has_bitfield && - !(mp_decoded.decoded.bitfield & BITFIELD_OK_TO_MQTT_MASK) && - (ch.settings.psk.size < 2 || (ch.settings.psk.size == 16 && memcmp(ch.settings.psk.bytes, defaultpsk, 16)) || - (ch.settings.psk.size == 32 && memcmp(ch.settings.psk.bytes, eventpsk, 32)))) - { - LOG_INFO("MQTT onSend - Not forwarding packet due to DontMqttMeBro flag\n"); - return; - } + // check for the lowest bit of the data bitfield set false, and the use of one of the default keys. + if (mp_decoded.from != nodeDB->getNodeNum() && mp_decoded.decoded.has_bitfield && + !(mp_decoded.decoded.bitfield & BITFIELD_OK_TO_MQTT_MASK) && + (ch.settings.psk.size < 2 || (ch.settings.psk.size == 16 && memcmp(ch.settings.psk.bytes, defaultpsk, 16)) || + (ch.settings.psk.size == 32 && memcmp(ch.settings.psk.bytes, eventpsk, 32)))) { + LOG_INFO("MQTT onSend - Not forwarding packet due to DontMqttMeBro flag\n"); + return; + } - if (strcmp(moduleConfig.mqtt.address, default_mqtt_address) == 0 && - (mp_decoded.decoded.portnum == meshtastic_PortNum_RANGE_TEST_APP || - mp_decoded.decoded.portnum == meshtastic_PortNum_DETECTION_SENSOR_APP)) - { - LOG_DEBUG("MQTT onSend - Ignoring range test or detection sensor message on public mqtt\n"); - return; - } - } - if (mp.pki_encrypted || ch.settings.uplink_enabled) - { - const char *channelId = mp.pki_encrypted ? "PKI" : channels.getGlobalId(chIndex); + if (strcmp(moduleConfig.mqtt.address, default_mqtt_address) == 0 && + (mp_decoded.decoded.portnum == meshtastic_PortNum_RANGE_TEST_APP || + mp_decoded.decoded.portnum == meshtastic_PortNum_DETECTION_SENSOR_APP)) { + LOG_DEBUG("MQTT onSend - Ignoring range test or detection sensor message on public mqtt\n"); + return; + } + } + if (mp.pki_encrypted || ch.settings.uplink_enabled) { + const char *channelId = mp.pki_encrypted ? "PKI" : channels.getGlobalId(chIndex); - meshtastic_ServiceEnvelope *env = mqttPool.allocZeroed(); - env->channel_id = (char *)channelId; - env->gateway_id = owner.id; + meshtastic_ServiceEnvelope *env = mqttPool.allocZeroed(); + env->channel_id = (char *)channelId; + env->gateway_id = owner.id; - LOG_DEBUG("MQTT onSend - Publishing "); - if (moduleConfig.mqtt.encryption_enabled) - { - env->packet = (meshtastic_MeshPacket *)∓ - LOG_DEBUG("encrypted message\n"); - } - else if (mp_decoded.which_payload_variant == - meshtastic_MeshPacket_decoded_tag) - { // Don't upload a still-encrypted PKI packet - env->packet = (meshtastic_MeshPacket *)&mp_decoded; - LOG_DEBUG("portnum %i message\n", env->packet->decoded.portnum); - } + LOG_DEBUG("MQTT onSend - Publishing "); + if (moduleConfig.mqtt.encryption_enabled) { + env->packet = (meshtastic_MeshPacket *)∓ + LOG_DEBUG("encrypted message\n"); + } else if (mp_decoded.which_payload_variant == + meshtastic_MeshPacket_decoded_tag) { // Don't upload a still-encrypted PKI packet + env->packet = (meshtastic_MeshPacket *)&mp_decoded; + LOG_DEBUG("portnum %i message\n", env->packet->decoded.portnum); + } - if (moduleConfig.mqtt.proxy_to_client_enabled || this->isConnectedDirectly()) - { - // FIXME - this size calculation is super sloppy, but it will go away once we dynamically alloc meshpackets - static uint8_t bytes[meshtastic_MeshPacket_size + 64]; - size_t numBytes = pb_encode_to_bytes(bytes, sizeof(bytes), &meshtastic_ServiceEnvelope_msg, env); - std::string topic = cryptTopic + channelId + "/" + owner.id; - LOG_DEBUG("MQTT Publish %s, %u bytes\n", topic.c_str(), numBytes); + if (moduleConfig.mqtt.proxy_to_client_enabled || this->isConnectedDirectly()) { + // FIXME - this size calculation is super sloppy, but it will go away once we dynamically alloc meshpackets + static uint8_t bytes[meshtastic_MeshPacket_size + 64]; + size_t numBytes = pb_encode_to_bytes(bytes, sizeof(bytes), &meshtastic_ServiceEnvelope_msg, env); + std::string topic = cryptTopic + channelId + "/" + owner.id; + LOG_DEBUG("MQTT Publish %s, %u bytes\n", topic.c_str(), numBytes); - publish(topic.c_str(), bytes, numBytes, false); + publish(topic.c_str(), bytes, numBytes, false); #if !defined(ARCH_NRF52) || defined(NRF52_USE_JSON) // JSON is not supported on nRF52, see issue #2804 ### Fixed by using ArduinoJson ### - if (moduleConfig.mqtt.json_enabled) - { - // handle json topic - auto jsonString = MeshPacketSerializer::JsonSerialize((meshtastic_MeshPacket *)&mp_decoded); - if (jsonString.length() != 0) - { - std::string topicJson = jsonTopic + channelId + "/" + owner.id; - LOG_INFO("JSON publish message to %s, %u bytes: %s\n", topicJson.c_str(), jsonString.length(), - jsonString.c_str()); - publish(topicJson.c_str(), jsonString.c_str(), false); - } - } + if (moduleConfig.mqtt.json_enabled) { + // handle json topic + auto jsonString = MeshPacketSerializer::JsonSerialize((meshtastic_MeshPacket *)&mp_decoded); + if (jsonString.length() != 0) { + std::string topicJson = jsonTopic + channelId + "/" + owner.id; + LOG_INFO("JSON publish message to %s, %u bytes: %s\n", topicJson.c_str(), jsonString.length(), + jsonString.c_str()); + publish(topicJson.c_str(), jsonString.c_str(), false); + } + } #endif // ARCH_NRF52 NRF52_USE_JSON - } - else - { - LOG_INFO("MQTT not connected, queueing packet\n"); - if (mqttQueue.numFree() == 0) - { - LOG_WARN("NOTE: MQTT queue is full, discarding oldest\n"); - meshtastic_ServiceEnvelope *d = mqttQueue.dequeuePtr(0); - if (d) - mqttPool.release(d); - } - // make a copy of serviceEnvelope and queue it - meshtastic_ServiceEnvelope *copied = mqttPool.allocCopy(*env); - assert(mqttQueue.enqueue(copied, 0)); - } - mqttPool.release(env); - } + } else { + LOG_INFO("MQTT not connected, queueing packet\n"); + if (mqttQueue.numFree() == 0) { + LOG_WARN("NOTE: MQTT queue is full, discarding oldest\n"); + meshtastic_ServiceEnvelope *d = mqttQueue.dequeuePtr(0); + if (d) + mqttPool.release(d); + } + // make a copy of serviceEnvelope and queue it + meshtastic_ServiceEnvelope *copied = mqttPool.allocCopy(*env); + assert(mqttQueue.enqueue(copied, 0)); + } + mqttPool.release(env); + } } void MQTT::perhapsReportToMap() { - if (!moduleConfig.mqtt.map_reporting_enabled || !(moduleConfig.mqtt.proxy_to_client_enabled || isConnectedDirectly())) - return; + if (!moduleConfig.mqtt.map_reporting_enabled || !(moduleConfig.mqtt.proxy_to_client_enabled || isConnectedDirectly())) + return; - if (millis() - last_report_to_map < map_publish_interval_msecs) - { - return; - } - else - { - if (map_position_precision == 0 || (localPosition.latitude_i == 0 && localPosition.longitude_i == 0)) - { - last_report_to_map = millis(); - if (map_position_precision == 0) - LOG_WARN("MQTT Map reporting is enabled, but precision is 0\n"); - if (localPosition.latitude_i == 0 && localPosition.longitude_i == 0) - LOG_WARN("MQTT Map reporting is enabled, but no position available.\n"); - return; - } + if (millis() - last_report_to_map < map_publish_interval_msecs) { + return; + } else { + if (map_position_precision == 0 || (localPosition.latitude_i == 0 && localPosition.longitude_i == 0)) { + last_report_to_map = millis(); + if (map_position_precision == 0) + LOG_WARN("MQTT Map reporting is enabled, but precision is 0\n"); + if (localPosition.latitude_i == 0 && localPosition.longitude_i == 0) + LOG_WARN("MQTT Map reporting is enabled, but no position available.\n"); + return; + } - // Allocate ServiceEnvelope and fill it - meshtastic_ServiceEnvelope *se = mqttPool.allocZeroed(); - se->channel_id = (char *)channels.getGlobalId(channels.getPrimaryIndex()); // Use primary channel as the channel_id - se->gateway_id = owner.id; + // Allocate ServiceEnvelope and fill it + meshtastic_ServiceEnvelope *se = mqttPool.allocZeroed(); + se->channel_id = (char *)channels.getGlobalId(channels.getPrimaryIndex()); // Use primary channel as the channel_id + se->gateway_id = owner.id; - // Allocate MeshPacket and fill it - meshtastic_MeshPacket *mp = packetPool.allocZeroed(); - mp->which_payload_variant = meshtastic_MeshPacket_decoded_tag; - mp->from = nodeDB->getNodeNum(); - mp->to = NODENUM_BROADCAST; - mp->decoded.portnum = meshtastic_PortNum_MAP_REPORT_APP; + // Allocate MeshPacket and fill it + meshtastic_MeshPacket *mp = packetPool.allocZeroed(); + mp->which_payload_variant = meshtastic_MeshPacket_decoded_tag; + mp->from = nodeDB->getNodeNum(); + mp->to = NODENUM_BROADCAST; + mp->decoded.portnum = meshtastic_PortNum_MAP_REPORT_APP; - // Fill MapReport message - meshtastic_MapReport mapReport = meshtastic_MapReport_init_default; - memcpy(mapReport.long_name, owner.long_name, sizeof(owner.long_name)); - memcpy(mapReport.short_name, owner.short_name, sizeof(owner.short_name)); - mapReport.role = config.device.role; - mapReport.hw_model = owner.hw_model; - strncpy(mapReport.firmware_version, optstr(APP_VERSION), sizeof(mapReport.firmware_version)); - mapReport.region = config.lora.region; - mapReport.modem_preset = config.lora.modem_preset; - mapReport.has_default_channel = channels.hasDefaultChannel(); + // Fill MapReport message + meshtastic_MapReport mapReport = meshtastic_MapReport_init_default; + memcpy(mapReport.long_name, owner.long_name, sizeof(owner.long_name)); + memcpy(mapReport.short_name, owner.short_name, sizeof(owner.short_name)); + mapReport.role = config.device.role; + mapReport.hw_model = owner.hw_model; + strncpy(mapReport.firmware_version, optstr(APP_VERSION), sizeof(mapReport.firmware_version)); + mapReport.region = config.lora.region; + mapReport.modem_preset = config.lora.modem_preset; + mapReport.has_default_channel = channels.hasDefaultChannel(); - // Set position with precision (same as in PositionModule) - if (map_position_precision < 32 && map_position_precision > 0) - { - mapReport.latitude_i = localPosition.latitude_i & (UINT32_MAX << (32 - map_position_precision)); - mapReport.longitude_i = localPosition.longitude_i & (UINT32_MAX << (32 - map_position_precision)); - mapReport.latitude_i += (1 << (31 - map_position_precision)); - mapReport.longitude_i += (1 << (31 - map_position_precision)); - } - else - { - mapReport.latitude_i = localPosition.latitude_i; - mapReport.longitude_i = localPosition.longitude_i; - } - mapReport.altitude = localPosition.altitude; - mapReport.position_precision = map_position_precision; + // Set position with precision (same as in PositionModule) + if (map_position_precision < 32 && map_position_precision > 0) { + mapReport.latitude_i = localPosition.latitude_i & (UINT32_MAX << (32 - map_position_precision)); + mapReport.longitude_i = localPosition.longitude_i & (UINT32_MAX << (32 - map_position_precision)); + mapReport.latitude_i += (1 << (31 - map_position_precision)); + mapReport.longitude_i += (1 << (31 - map_position_precision)); + } else { + mapReport.latitude_i = localPosition.latitude_i; + mapReport.longitude_i = localPosition.longitude_i; + } + mapReport.altitude = localPosition.altitude; + mapReport.position_precision = map_position_precision; - mapReport.num_online_local_nodes = nodeDB->getNumOnlineMeshNodes(true); + mapReport.num_online_local_nodes = nodeDB->getNumOnlineMeshNodes(true); - // Encode MapReport message and set it to MeshPacket in ServiceEnvelope - mp->decoded.payload.size = pb_encode_to_bytes(mp->decoded.payload.bytes, sizeof(mp->decoded.payload.bytes), - &meshtastic_MapReport_msg, &mapReport); - se->packet = mp; + // Encode MapReport message and set it to MeshPacket in ServiceEnvelope + mp->decoded.payload.size = pb_encode_to_bytes(mp->decoded.payload.bytes, sizeof(mp->decoded.payload.bytes), + &meshtastic_MapReport_msg, &mapReport); + se->packet = mp; - // FIXME - this size calculation is super sloppy, but it will go away once we dynamically alloc meshpackets - static uint8_t bytes[meshtastic_MeshPacket_size + 64]; - size_t numBytes = pb_encode_to_bytes(bytes, sizeof(bytes), &meshtastic_ServiceEnvelope_msg, se); + // FIXME - this size calculation is super sloppy, but it will go away once we dynamically alloc meshpackets + static uint8_t bytes[meshtastic_MeshPacket_size + 64]; + size_t numBytes = pb_encode_to_bytes(bytes, sizeof(bytes), &meshtastic_ServiceEnvelope_msg, se); - LOG_INFO("MQTT Publish map report to %s\n", mapTopic.c_str()); - publish(mapTopic.c_str(), bytes, numBytes, false); + LOG_INFO("MQTT Publish map report to %s\n", mapTopic.c_str()); + publish(mapTopic.c_str(), bytes, numBytes, false); - // Release the allocated memory for ServiceEnvelope and MeshPacket - mqttPool.release(se); - packetPool.release(mp); + // Release the allocated memory for ServiceEnvelope and MeshPacket + mqttPool.release(se); + packetPool.release(mp); - // Update the last report time - last_report_to_map = millis(); - } + // Update the last report time + last_report_to_map = millis(); + } } bool MQTT::isValidJsonEnvelope(JSONObject &json) { - // if "sender" is provided, avoid processing packets we uplinked - return (json.find("sender") != json.end() ? (json["sender"]->AsString().compare(owner.id) != 0) : true) && - (json.find("hopLimit") != json.end() ? json["hopLimit"]->IsNumber() : true) && // hop limit should be a number - (json.find("from") != json.end()) && json["from"]->IsNumber() && - (json["from"]->AsNumber() == nodeDB->getNodeNum()) && // only accept message if the "from" is us - (json.find("type") != json.end()) && json["type"]->IsString() && // should specify a type - (json.find("payload") != json.end()); // should have a payload + // if "sender" is provided, avoid processing packets we uplinked + return (json.find("sender") != json.end() ? (json["sender"]->AsString().compare(owner.id) != 0) : true) && + (json.find("hopLimit") != json.end() ? json["hopLimit"]->IsNumber() : true) && // hop limit should be a number + (json.find("from") != json.end()) && json["from"]->IsNumber() && + (json["from"]->AsNumber() == nodeDB->getNodeNum()) && // only accept message if the "from" is us + (json.find("type") != json.end()) && json["type"]->IsString() && // should specify a type + (json.find("payload") != json.end()); // should have a payload } diff --git a/src/platform/nrf52/NRF52Bluetooth.cpp b/src/platform/nrf52/NRF52Bluetooth.cpp index 9ed2a0d6a..817583821 100644 --- a/src/platform/nrf52/NRF52Bluetooth.cpp +++ b/src/platform/nrf52/NRF52Bluetooth.cpp @@ -32,23 +32,23 @@ static uint16_t connectionHandle; class BluetoothPhoneAPI : public PhoneAPI { - /** - * Subclasses can use this as a hook to provide custom notifications for their transport (i.e. bluetooth notifies) - */ - virtual void onNowHasData(uint32_t fromRadioNum) override - { - PhoneAPI::onNowHasData(fromRadioNum); + /** + * Subclasses can use this as a hook to provide custom notifications for their transport (i.e. bluetooth notifies) + */ + virtual void onNowHasData(uint32_t fromRadioNum) override + { + PhoneAPI::onNowHasData(fromRadioNum); - LOG_INFO("BLE notify fromNum\n"); - fromNum.notify32(fromRadioNum); - } + LOG_INFO("BLE notify fromNum\n"); + fromNum.notify32(fromRadioNum); + } - /// Check the current underlying physical link to see if the client is currently connected - virtual bool checkIsConnected() override - { - BLEConnection *connection = Bluefruit.Connection(connectionHandle); - return connection->connected(); - } + /// Check the current underlying physical link to see if the client is currently connected + virtual bool checkIsConnected() override + { + BLEConnection *connection = Bluefruit.Connection(connectionHandle); + return connection->connected(); + } }; static BluetoothPhoneAPI *bluetoothPhoneAPI; @@ -56,12 +56,12 @@ static BluetoothPhoneAPI *bluetoothPhoneAPI; void onConnect(uint16_t conn_handle) { - // Get the reference to current connection - BLEConnection *connection = Bluefruit.Connection(conn_handle); - connectionHandle = conn_handle; - char central_name[32] = {0}; - connection->getPeerName(central_name, sizeof(central_name)); - LOG_INFO("BLE Connected to %s\n", central_name); + // Get the reference to current connection + BLEConnection *connection = Bluefruit.Connection(conn_handle); + connectionHandle = conn_handle; + char central_name[32] = {0}; + connection->getPeerName(central_name, sizeof(central_name)); + LOG_INFO("BLE Connected to %s\n", central_name); } /** * Callback invoked when a connection is dropped @@ -70,261 +70,248 @@ void onConnect(uint16_t conn_handle) */ void onDisconnect(uint16_t conn_handle, uint8_t reason) { - // FIXME - we currently assume only one active connection - LOG_INFO("BLE Disconnected, reason = 0x%x\n", reason); + // FIXME - we currently assume only one active connection + LOG_INFO("BLE Disconnected, reason = 0x%x\n", reason); } void onCccd(uint16_t conn_hdl, BLECharacteristic *chr, uint16_t cccd_value) { - // Display the raw request packet - LOG_INFO("CCCD Updated: %u\n", cccd_value); - // Check the characteristic this CCCD update is associated with in case - // this handler is used for multiple CCCD records. + // Display the raw request packet + LOG_INFO("CCCD Updated: %u\n", cccd_value); + // Check the characteristic this CCCD update is associated with in case + // this handler is used for multiple CCCD records. - // According to the GATT spec: cccd value = 0x0001 means notifications are enabled - // and cccd value = 0x0002 means indications are enabled + // According to the GATT spec: cccd value = 0x0001 means notifications are enabled + // and cccd value = 0x0002 means indications are enabled - if (chr->uuid == fromNum.uuid || chr->uuid == logRadio.uuid) - { - auto result = cccd_value == 2 ? chr->indicateEnabled(conn_hdl) : chr->notifyEnabled(conn_hdl); - if (result) - { - LOG_INFO("Notify/Indicate enabled\n"); - } - else - { - LOG_INFO("Notify/Indicate disabled\n"); - } - } + if (chr->uuid == fromNum.uuid || chr->uuid == logRadio.uuid) { + auto result = cccd_value == 2 ? chr->indicateEnabled(conn_hdl) : chr->notifyEnabled(conn_hdl); + if (result) { + LOG_INFO("Notify/Indicate enabled\n"); + } else { + LOG_INFO("Notify/Indicate disabled\n"); + } + } } void startAdv(void) { - // Advertising packet - Bluefruit.Advertising.addFlags(BLE_GAP_ADV_FLAGS_LE_ONLY_GENERAL_DISC_MODE); - // IncludeService UUID - // Bluefruit.ScanResponse.addService(meshBleService); - Bluefruit.ScanResponse.addTxPower(); - Bluefruit.ScanResponse.addName(); - // Include Name - // Bluefruit.Advertising.addName(); - Bluefruit.Advertising.addService(meshBleService); - /* Start Advertising - * - Enable auto advertising if disconnected - * - Interval: fast mode = 20 ms, slow mode = 152.5 ms - * - Timeout for fast mode is 30 seconds - * - Start(timeout) with timeout = 0 will advertise forever (until connected) - * - * For recommended advertising interval - * https://developer.apple.com/library/content/qa/qa1931/_index.html - */ - Bluefruit.Advertising.restartOnDisconnect(true); - Bluefruit.Advertising.setInterval(32, 244); // in unit of 0.625 ms - Bluefruit.Advertising.setFastTimeout(30); // number of seconds in fast mode - Bluefruit.Advertising.start(0); // 0 = Don't stop advertising after n seconds. FIXME, we should stop advertising after X + // Advertising packet + Bluefruit.Advertising.addFlags(BLE_GAP_ADV_FLAGS_LE_ONLY_GENERAL_DISC_MODE); + // IncludeService UUID + // Bluefruit.ScanResponse.addService(meshBleService); + Bluefruit.ScanResponse.addTxPower(); + Bluefruit.ScanResponse.addName(); + // Include Name + // Bluefruit.Advertising.addName(); + Bluefruit.Advertising.addService(meshBleService); + /* Start Advertising + * - Enable auto advertising if disconnected + * - Interval: fast mode = 20 ms, slow mode = 152.5 ms + * - Timeout for fast mode is 30 seconds + * - Start(timeout) with timeout = 0 will advertise forever (until connected) + * + * For recommended advertising interval + * https://developer.apple.com/library/content/qa/qa1931/_index.html + */ + Bluefruit.Advertising.restartOnDisconnect(true); + Bluefruit.Advertising.setInterval(32, 244); // in unit of 0.625 ms + Bluefruit.Advertising.setFastTimeout(30); // number of seconds in fast mode + Bluefruit.Advertising.start(0); // 0 = Don't stop advertising after n seconds. FIXME, we should stop advertising after X } // Just ack that the caller is allowed to read static void authorizeRead(uint16_t conn_hdl) { - ble_gatts_rw_authorize_reply_params_t reply = {.type = BLE_GATTS_AUTHORIZE_TYPE_READ}; - reply.params.write.gatt_status = BLE_GATT_STATUS_SUCCESS; - sd_ble_gatts_rw_authorize_reply(conn_hdl, &reply); + ble_gatts_rw_authorize_reply_params_t reply = {.type = BLE_GATTS_AUTHORIZE_TYPE_READ}; + reply.params.write.gatt_status = BLE_GATT_STATUS_SUCCESS; + sd_ble_gatts_rw_authorize_reply(conn_hdl, &reply); } /** * client is starting read, pull the bytes from our API class */ void onFromRadioAuthorize(uint16_t conn_hdl, BLECharacteristic *chr, ble_gatts_evt_read_t *request) { - if (request->offset == 0) - { - // If the read is long, we will get multiple authorize invocations - we only populate data on the first - size_t numBytes = bluetoothPhoneAPI->getFromRadio(fromRadioBytes); - // Someone is going to read our value as soon as this callback returns. So fill it with the next message in the queue - // or make empty if the queue is empty - fromRadio.write(fromRadioBytes, numBytes); - } - else - { - // LOG_INFO("Ignoring successor read\n"); - } - authorizeRead(conn_hdl); + if (request->offset == 0) { + // If the read is long, we will get multiple authorize invocations - we only populate data on the first + size_t numBytes = bluetoothPhoneAPI->getFromRadio(fromRadioBytes); + // Someone is going to read our value as soon as this callback returns. So fill it with the next message in the queue + // or make empty if the queue is empty + fromRadio.write(fromRadioBytes, numBytes); + } else { + // LOG_INFO("Ignoring successor read\n"); + } + authorizeRead(conn_hdl); } void onToRadioWrite(uint16_t conn_hdl, BLECharacteristic *chr, uint8_t *data, uint16_t len) { - LOG_INFO("toRadioWriteCb data %p, len %u\n", data, len); - bluetoothPhoneAPI->handleToRadio(data, len); + LOG_INFO("toRadioWriteCb data %p, len %u\n", data, len); + bluetoothPhoneAPI->handleToRadio(data, len); } void setupMeshService(void) { - bluetoothPhoneAPI = new BluetoothPhoneAPI(); - meshBleService.begin(); - // Note: You must call .begin() on the BLEService before calling .begin() on - // any characteristic(s) within that service definition.. Calling .begin() on - // a BLECharacteristic will cause it to be added to the last BLEService that - // was 'begin()'ed! - auto secMode = - config.bluetooth.mode == meshtastic_Config_BluetoothConfig_PairingMode_NO_PIN ? SECMODE_OPEN : SECMODE_ENC_NO_MITM; - fromNum.setProperties(CHR_PROPS_NOTIFY | CHR_PROPS_READ); - fromNum.setPermission(secMode, SECMODE_NO_ACCESS); // FIXME, secure this!!! - fromNum.setFixedLen( - 0); // Variable len (either 0 or 4) FIXME consider changing protocol so it is fixed 4 byte len, where 0 means empty - fromNum.setMaxLen(4); - fromNum.setCccdWriteCallback(onCccd); // Optionally capture CCCD updates - // We don't yet need to hook the fromNum auth callback - // fromNum.setReadAuthorizeCallback(fromNumAuthorizeCb); - fromNum.write32(0); // Provide default fromNum of 0 - fromNum.begin(); + bluetoothPhoneAPI = new BluetoothPhoneAPI(); + meshBleService.begin(); + // Note: You must call .begin() on the BLEService before calling .begin() on + // any characteristic(s) within that service definition.. Calling .begin() on + // a BLECharacteristic will cause it to be added to the last BLEService that + // was 'begin()'ed! + auto secMode = + config.bluetooth.mode == meshtastic_Config_BluetoothConfig_PairingMode_NO_PIN ? SECMODE_OPEN : SECMODE_ENC_NO_MITM; + fromNum.setProperties(CHR_PROPS_NOTIFY | CHR_PROPS_READ); + fromNum.setPermission(secMode, SECMODE_NO_ACCESS); // FIXME, secure this!!! + fromNum.setFixedLen( + 0); // Variable len (either 0 or 4) FIXME consider changing protocol so it is fixed 4 byte len, where 0 means empty + fromNum.setMaxLen(4); + fromNum.setCccdWriteCallback(onCccd); // Optionally capture CCCD updates + // We don't yet need to hook the fromNum auth callback + // fromNum.setReadAuthorizeCallback(fromNumAuthorizeCb); + fromNum.write32(0); // Provide default fromNum of 0 + fromNum.begin(); - fromRadio.setProperties(CHR_PROPS_READ); - fromRadio.setPermission(secMode, SECMODE_NO_ACCESS); - fromRadio.setMaxLen(sizeof(fromRadioBytes)); - fromRadio.setReadAuthorizeCallback( - onFromRadioAuthorize, - false); // We don't call this callback via the adafruit queue, because we can safely run in the BLE context - fromRadio.setBuffer(fromRadioBytes, sizeof(fromRadioBytes)); // we preallocate our fromradio buffer so we won't waste space - // for two copies - fromRadio.begin(); + fromRadio.setProperties(CHR_PROPS_READ); + fromRadio.setPermission(secMode, SECMODE_NO_ACCESS); + fromRadio.setMaxLen(sizeof(fromRadioBytes)); + fromRadio.setReadAuthorizeCallback( + onFromRadioAuthorize, + false); // We don't call this callback via the adafruit queue, because we can safely run in the BLE context + fromRadio.setBuffer(fromRadioBytes, sizeof(fromRadioBytes)); // we preallocate our fromradio buffer so we won't waste space + // for two copies + fromRadio.begin(); - toRadio.setProperties(CHR_PROPS_WRITE); - toRadio.setPermission(secMode, secMode); // FIXME secure this! - toRadio.setFixedLen(0); - toRadio.setMaxLen(512); - toRadio.setBuffer(toRadioBytes, sizeof(toRadioBytes)); - // We don't call this callback via the adafruit queue, because we can safely run in the BLE context - toRadio.setWriteCallback(onToRadioWrite, false); - toRadio.begin(); + toRadio.setProperties(CHR_PROPS_WRITE); + toRadio.setPermission(secMode, secMode); // FIXME secure this! + toRadio.setFixedLen(0); + toRadio.setMaxLen(512); + toRadio.setBuffer(toRadioBytes, sizeof(toRadioBytes)); + // We don't call this callback via the adafruit queue, because we can safely run in the BLE context + toRadio.setWriteCallback(onToRadioWrite, false); + toRadio.begin(); - logRadio.setProperties(CHR_PROPS_INDICATE | CHR_PROPS_NOTIFY | CHR_PROPS_READ); - logRadio.setPermission(secMode, SECMODE_NO_ACCESS); - logRadio.setMaxLen(512); - logRadio.setCccdWriteCallback(onCccd); - logRadio.write32(0); - logRadio.begin(); + logRadio.setProperties(CHR_PROPS_INDICATE | CHR_PROPS_NOTIFY | CHR_PROPS_READ); + logRadio.setPermission(secMode, SECMODE_NO_ACCESS); + logRadio.setMaxLen(512); + logRadio.setCccdWriteCallback(onCccd); + logRadio.write32(0); + logRadio.begin(); } static uint32_t configuredPasskey; void NRF52Bluetooth::shutdown() { - // Shutdown bluetooth for minimum power draw - LOG_INFO("Disable NRF52 bluetooth\n"); - uint8_t connection_num = Bluefruit.connected(); - if (connection_num) - { - for (uint8_t i = 0; i < connection_num; i++) - { - LOG_INFO("NRF52 bluetooth disconnecting handle %d\n", i); - Bluefruit.disconnect(i); - } - delay(100); // wait for ondisconnect; - } - Bluefruit.Advertising.stop(); + // Shutdown bluetooth for minimum power draw + LOG_INFO("Disable NRF52 bluetooth\n"); + uint8_t connection_num = Bluefruit.connected(); + if (connection_num) { + for (uint8_t i = 0; i < connection_num; i++) { + LOG_INFO("NRF52 bluetooth disconnecting handle %d\n", i); + Bluefruit.disconnect(i); + } + delay(100); // wait for ondisconnect; + } + Bluefruit.Advertising.stop(); } void NRF52Bluetooth::startDisabled() { - // Setup Bluetooth - nrf52Bluetooth->setup(); - // Shutdown bluetooth for minimum power draw - Bluefruit.Advertising.stop(); - Bluefruit.setTxPower(-40); // Minimum power - LOG_INFO("Disabling NRF52 Bluetooth. (Workaround: tx power min, advertising stopped)\n"); + // Setup Bluetooth + nrf52Bluetooth->setup(); + // Shutdown bluetooth for minimum power draw + Bluefruit.Advertising.stop(); + Bluefruit.setTxPower(-40); // Minimum power + LOG_INFO("Disabling NRF52 Bluetooth. (Workaround: tx power min, advertising stopped)\n"); } bool NRF52Bluetooth::isConnected() { - return Bluefruit.connected(connectionHandle); + return Bluefruit.connected(connectionHandle); } int NRF52Bluetooth::getRssi() { - return 0; // FIXME figure out where to source this + return 0; // FIXME figure out where to source this } void NRF52Bluetooth::setup() { - // Initialise the Bluefruit module - LOG_INFO("Initialize the Bluefruit nRF52 module\n"); - Bluefruit.autoConnLed(false); - Bluefruit.configPrphBandwidth(BANDWIDTH_MAX); - Bluefruit.begin(); - // Clear existing data. - Bluefruit.Advertising.stop(); - Bluefruit.Advertising.clearData(); - Bluefruit.ScanResponse.clearData(); - if (config.bluetooth.mode != meshtastic_Config_BluetoothConfig_PairingMode_NO_PIN) - { - configuredPasskey = config.bluetooth.mode == meshtastic_Config_BluetoothConfig_PairingMode_FIXED_PIN - ? config.bluetooth.fixed_pin - : random(100000, 999999); - auto pinString = std::to_string(configuredPasskey); - LOG_INFO("Bluetooth pin set to '%i'\n", configuredPasskey); - Bluefruit.Security.setPIN(pinString.c_str()); - Bluefruit.Security.setIOCaps(true, false, false); - Bluefruit.Security.setPairPasskeyCallback(NRF52Bluetooth::onPairingPasskey); - Bluefruit.Security.setPairCompleteCallback(NRF52Bluetooth::onPairingCompleted); - Bluefruit.Security.setSecuredCallback(NRF52Bluetooth::onConnectionSecured); - meshBleService.setPermission(SECMODE_ENC_WITH_MITM, SECMODE_ENC_WITH_MITM); - } - else - { - Bluefruit.Security.setIOCaps(false, false, false); - meshBleService.setPermission(SECMODE_OPEN, SECMODE_OPEN); - } - // Set the advertised device name (keep it short!) - Bluefruit.setName(getDeviceName()); - // Set the connect/disconnect callback handlers - Bluefruit.Periph.setConnectCallback(onConnect); - Bluefruit.Periph.setDisconnectCallback(onDisconnect); + // Initialise the Bluefruit module + LOG_INFO("Initialize the Bluefruit nRF52 module\n"); + Bluefruit.autoConnLed(false); + Bluefruit.configPrphBandwidth(BANDWIDTH_MAX); + Bluefruit.begin(); + // Clear existing data. + Bluefruit.Advertising.stop(); + Bluefruit.Advertising.clearData(); + Bluefruit.ScanResponse.clearData(); + if (config.bluetooth.mode != meshtastic_Config_BluetoothConfig_PairingMode_NO_PIN) { + configuredPasskey = config.bluetooth.mode == meshtastic_Config_BluetoothConfig_PairingMode_FIXED_PIN + ? config.bluetooth.fixed_pin + : random(100000, 999999); + auto pinString = std::to_string(configuredPasskey); + LOG_INFO("Bluetooth pin set to '%i'\n", configuredPasskey); + Bluefruit.Security.setPIN(pinString.c_str()); + Bluefruit.Security.setIOCaps(true, false, false); + Bluefruit.Security.setPairPasskeyCallback(NRF52Bluetooth::onPairingPasskey); + Bluefruit.Security.setPairCompleteCallback(NRF52Bluetooth::onPairingCompleted); + Bluefruit.Security.setSecuredCallback(NRF52Bluetooth::onConnectionSecured); + meshBleService.setPermission(SECMODE_ENC_WITH_MITM, SECMODE_ENC_WITH_MITM); + } else { + Bluefruit.Security.setIOCaps(false, false, false); + meshBleService.setPermission(SECMODE_OPEN, SECMODE_OPEN); + } + // Set the advertised device name (keep it short!) + Bluefruit.setName(getDeviceName()); + // Set the connect/disconnect callback handlers + Bluefruit.Periph.setConnectCallback(onConnect); + Bluefruit.Periph.setDisconnectCallback(onDisconnect); #ifndef BLE_DFU_SECURE - bledfu.setPermission(SECMODE_ENC_WITH_MITM, SECMODE_ENC_WITH_MITM); - bledfu.begin(); // Install the DFU helper + bledfu.setPermission(SECMODE_ENC_WITH_MITM, SECMODE_ENC_WITH_MITM); + bledfu.begin(); // Install the DFU helper #else - bledfusecure.setPermission(SECMODE_ENC_WITH_MITM, SECMODE_ENC_WITH_MITM); // add by WayenWeng - bledfusecure.begin(); // Install the DFU helper + bledfusecure.setPermission(SECMODE_ENC_WITH_MITM, SECMODE_ENC_WITH_MITM); // add by WayenWeng + bledfusecure.begin(); // Install the DFU helper #endif - // Configure and Start the Device Information Service - LOG_INFO("Configuring the Device Information Service\n"); - bledis.setModel(optstr(HW_VERSION)); - bledis.setFirmwareRev(optstr(APP_VERSION)); - bledis.begin(); - // Start the BLE Battery Service and set it to 100% - LOG_INFO("Configuring the Battery Service\n"); - blebas.begin(); - blebas.write(0); // Unknown battery level for now - // Setup the Heart Rate Monitor service using - // BLEService and BLECharacteristic classes - LOG_INFO("Configuring the Mesh bluetooth service\n"); - setupMeshService(); - // Setup the advertising packet(s) - LOG_INFO("Setting up the advertising payload(s)\n"); - startAdv(); - LOG_INFO("Advertising\n"); + // Configure and Start the Device Information Service + LOG_INFO("Configuring the Device Information Service\n"); + bledis.setModel(optstr(HW_VERSION)); + bledis.setFirmwareRev(optstr(APP_VERSION)); + bledis.begin(); + // Start the BLE Battery Service and set it to 100% + LOG_INFO("Configuring the Battery Service\n"); + blebas.begin(); + blebas.write(0); // Unknown battery level for now + // Setup the Heart Rate Monitor service using + // BLEService and BLECharacteristic classes + LOG_INFO("Configuring the Mesh bluetooth service\n"); + setupMeshService(); + // Setup the advertising packet(s) + LOG_INFO("Setting up the advertising payload(s)\n"); + startAdv(); + LOG_INFO("Advertising\n"); } void NRF52Bluetooth::resumeAdvertising() { - Bluefruit.Advertising.restartOnDisconnect(true); - Bluefruit.Advertising.setInterval(32, 244); // in unit of 0.625 ms - Bluefruit.Advertising.setFastTimeout(30); // number of seconds in fast mode - Bluefruit.Advertising.start(0); + Bluefruit.Advertising.restartOnDisconnect(true); + Bluefruit.Advertising.setInterval(32, 244); // in unit of 0.625 ms + Bluefruit.Advertising.setFastTimeout(30); // number of seconds in fast mode + Bluefruit.Advertising.start(0); } /// Given a level between 0-100, update the BLE attribute void updateBatteryLevel(uint8_t level) { - blebas.write(level); + blebas.write(level); } void NRF52Bluetooth::clearBonds() { - LOG_INFO("Clearing bluetooth bonds!\n"); - bond_print_list(BLE_GAP_ROLE_PERIPH); - bond_print_list(BLE_GAP_ROLE_CENTRAL); - Bluefruit.Periph.clearBonds(); - Bluefruit.Central.clearBonds(); + LOG_INFO("Clearing bluetooth bonds!\n"); + bond_print_list(BLE_GAP_ROLE_PERIPH); + bond_print_list(BLE_GAP_ROLE_CENTRAL); + Bluefruit.Periph.clearBonds(); + Bluefruit.Central.clearBonds(); } void NRF52Bluetooth::onConnectionSecured(uint16_t conn_handle) { - LOG_INFO("BLE connection secured\n"); + LOG_INFO("BLE connection secured\n"); } bool NRF52Bluetooth::onPairingPasskey(uint16_t conn_handle, uint8_t const passkey[6], bool match_request) { - LOG_INFO("BLE pairing process started with passkey %.3s %.3s\n", passkey, passkey + 3); - powerFSM.trigger(EVENT_BLUETOOTH_PAIR); + LOG_INFO("BLE pairing process started with passkey %.3s %.3s\n", passkey, passkey + 3); + powerFSM.trigger(EVENT_BLUETOOTH_PAIR); #if !defined(MESHTASTIC_EXCLUDE_SCREEN) - screen->startAlert([](OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y) -> void - { + screen->startAlert([](OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y) -> void { char btPIN[16] = "888888"; snprintf(btPIN, sizeof(btPIN), "%06u", configuredPasskey); int x_offset = display->width() / 2; @@ -347,35 +334,34 @@ bool NRF52Bluetooth::onPairingPasskey(uint16_t conn_handle, uint8_t const passke String deviceName = "Name: "; deviceName.concat(getDeviceName()); y_offset = display->height() == 64 ? y_offset + FONT_HEIGHT_LARGE - 6 : y_offset + FONT_HEIGHT_LARGE + 5; - display->drawString(x_offset + x, y_offset + y, deviceName); }); + display->drawString(x_offset + x, y_offset + y, deviceName); + }); #endif - if (match_request) - { - uint32_t start_time = millis(); - while (millis() < start_time + 30000) - { - if (!Bluefruit.connected(conn_handle)) - break; - } - } - LOG_INFO("BLE passkey pairing: match_request=%i\n", match_request); - return true; + if (match_request) { + uint32_t start_time = millis(); + while (millis() < start_time + 30000) { + if (!Bluefruit.connected(conn_handle)) + break; + } + } + LOG_INFO("BLE passkey pairing: match_request=%i\n", match_request); + return true; } void NRF52Bluetooth::onPairingCompleted(uint16_t conn_handle, uint8_t auth_status) { - if (auth_status == BLE_GAP_SEC_STATUS_SUCCESS) - LOG_INFO("BLE pairing success\n"); - else - LOG_INFO("BLE pairing failed\n"); - screen->endAlert(); + if (auth_status == BLE_GAP_SEC_STATUS_SUCCESS) + LOG_INFO("BLE pairing success\n"); + else + LOG_INFO("BLE pairing failed\n"); + screen->endAlert(); } void NRF52Bluetooth::sendLog(const uint8_t *logMessage, size_t length) { - if (!isConnected() || length > 512) - return; - if (logRadio.indicateEnabled()) - logRadio.indicate(logMessage, (uint16_t)length); - else - logRadio.notify(logMessage, (uint16_t)length); + if (!isConnected() || length > 512) + return; + if (logRadio.indicateEnabled()) + logRadio.indicate(logMessage, (uint16_t)length); + else + logRadio.notify(logMessage, (uint16_t)length); } \ No newline at end of file From 9f3a1c121404960bdf917082d5ba68712101a4c7 Mon Sep 17 00:00:00 2001 From: GUVWAF Date: Thu, 12 Sep 2024 19:12:57 +0200 Subject: [PATCH 10/88] Trunk fmt --- src/AccelerometerThread.h | 2 +- src/mqtt/MQTT.cpp | 11 +- src/platform/nrf52/NRF52Bluetooth.cpp | 12 +- .../MeshPacketSerializer_nRF52.cpp | 694 ++++++++---------- 4 files changed, 329 insertions(+), 390 deletions(-) diff --git a/src/AccelerometerThread.h b/src/AccelerometerThread.h index 37e7aab0d..7c133d9ab 100644 --- a/src/AccelerometerThread.h +++ b/src/AccelerometerThread.h @@ -95,7 +95,7 @@ class AccelerometerThread : public concurrency::OSThread return 500; } #if defined(RAK_4631) -#if !defined (MESHTASTIC_EXCLUDE_SCREEN) +#if !defined(MESHTASTIC_EXCLUDE_SCREEN) } else if (acceleremoter_type == ScanI2C::DeviceType::BMX160) { sBmx160SensorData_t magAccel; sBmx160SensorData_t gAccel; diff --git a/src/mqtt/MQTT.cpp b/src/mqtt/MQTT.cpp index a4921e684..fa8e2745c 100644 --- a/src/mqtt/MQTT.cpp +++ b/src/mqtt/MQTT.cpp @@ -378,8 +378,9 @@ void MQTT::sendSubscriptions() hasDownlink = true; std::string topic = cryptTopic + channels.getGlobalId(i) + "/+"; LOG_INFO("Subscribing to %s\n", topic.c_str()); - pubSub.subscribe(topic.c_str(), 1); // FIXME, is QOS 1 right? -#if !defined(ARCH_NRF52) || defined(NRF52_USE_JSON) // JSON is not supported on nRF52, see issue #2804 ### Fixed by using ArduinoJSON ### + pubSub.subscribe(topic.c_str(), 1); // FIXME, is QOS 1 right? +#if !defined(ARCH_NRF52) || \ + defined(NRF52_USE_JSON) // JSON is not supported on nRF52, see issue #2804 ### Fixed by using ArduinoJSON ### if (moduleConfig.mqtt.json_enabled == true) { std::string topicDecoded = jsonTopic + channels.getGlobalId(i) + "/+"; LOG_INFO("Subscribing to %s\n", topicDecoded.c_str()); @@ -480,7 +481,8 @@ void MQTT::publishQueuedMessages() publish(topic.c_str(), bytes, numBytes, false); -#if !defined(ARCH_NRF52) || defined(NRF52_USE_JSON) // JSON is not supported on nRF52, see issue #2804 ### Fixed by using ArduinoJson ### +#if !defined(ARCH_NRF52) || \ + defined(NRF52_USE_JSON) // JSON is not supported on nRF52, see issue #2804 ### Fixed by using ArduinoJson ### if (moduleConfig.mqtt.json_enabled) { // handle json topic auto jsonString = MeshPacketSerializer::JsonSerialize(env->packet); @@ -562,7 +564,8 @@ void MQTT::onSend(const meshtastic_MeshPacket &mp, const meshtastic_MeshPacket & publish(topic.c_str(), bytes, numBytes, false); -#if !defined(ARCH_NRF52) || defined(NRF52_USE_JSON) // JSON is not supported on nRF52, see issue #2804 ### Fixed by using ArduinoJson ### +#if !defined(ARCH_NRF52) || \ + defined(NRF52_USE_JSON) // JSON is not supported on nRF52, see issue #2804 ### Fixed by using ArduinoJson ### if (moduleConfig.mqtt.json_enabled) { // handle json topic auto jsonString = MeshPacketSerializer::JsonSerialize((meshtastic_MeshPacket *)&mp_decoded); diff --git a/src/platform/nrf52/NRF52Bluetooth.cpp b/src/platform/nrf52/NRF52Bluetooth.cpp index 817583821..2e9dbc1f8 100644 --- a/src/platform/nrf52/NRF52Bluetooth.cpp +++ b/src/platform/nrf52/NRF52Bluetooth.cpp @@ -19,7 +19,7 @@ static BLEBas blebas; // BAS (Battery Service) helper class instance #ifndef BLE_DFU_SECURE static BLEDfu bledfu; // DFU software update helper service #else -static BLEDfuSecure bledfusecure; // DFU software update helper service +static BLEDfuSecure bledfusecure; // DFU software update helper service #endif // This scratch buffer is used for various bluetooth reads/writes - but it is safe because only one bt operation can be in @@ -114,8 +114,8 @@ void startAdv(void) */ Bluefruit.Advertising.restartOnDisconnect(true); Bluefruit.Advertising.setInterval(32, 244); // in unit of 0.625 ms - Bluefruit.Advertising.setFastTimeout(30); // number of seconds in fast mode - Bluefruit.Advertising.start(0); // 0 = Don't stop advertising after n seconds. FIXME, we should stop advertising after X + Bluefruit.Advertising.setFastTimeout(30); // number of seconds in fast mode + Bluefruit.Advertising.start(0); // 0 = Don't stop advertising after n seconds. FIXME, we should stop advertising after X } // Just ack that the caller is allowed to read static void authorizeRead(uint16_t conn_hdl) @@ -172,7 +172,7 @@ void setupMeshService(void) fromRadio.setMaxLen(sizeof(fromRadioBytes)); fromRadio.setReadAuthorizeCallback( onFromRadioAuthorize, - false); // We don't call this callback via the adafruit queue, because we can safely run in the BLE context + false); // We don't call this callback via the adafruit queue, because we can safely run in the BLE context fromRadio.setBuffer(fromRadioBytes, sizeof(fromRadioBytes)); // we preallocate our fromradio buffer so we won't waste space // for two copies fromRadio.begin(); @@ -262,7 +262,7 @@ void NRF52Bluetooth::setup() bledfu.begin(); // Install the DFU helper #else bledfusecure.setPermission(SECMODE_ENC_WITH_MITM, SECMODE_ENC_WITH_MITM); // add by WayenWeng - bledfusecure.begin(); // Install the DFU helper + bledfusecure.begin(); // Install the DFU helper #endif // Configure and Start the Device Information Service LOG_INFO("Configuring the Device Information Service\n"); @@ -286,7 +286,7 @@ void NRF52Bluetooth::resumeAdvertising() { Bluefruit.Advertising.restartOnDisconnect(true); Bluefruit.Advertising.setInterval(32, 244); // in unit of 0.625 ms - Bluefruit.Advertising.setFastTimeout(30); // number of seconds in fast mode + Bluefruit.Advertising.setFastTimeout(30); // number of seconds in fast mode Bluefruit.Advertising.start(0); } /// Given a level between 0-100, update the BLE attribute diff --git a/src/serialization/MeshPacketSerializer_nRF52.cpp b/src/serialization/MeshPacketSerializer_nRF52.cpp index 8c58fba27..cd3aa1630 100644 --- a/src/serialization/MeshPacketSerializer_nRF52.cpp +++ b/src/serialization/MeshPacketSerializer_nRF52.cpp @@ -1,417 +1,353 @@ #ifdef NRF52_USE_JSON #warning 'Using nRF52 Serializer' -#include "MeshPacketSerializer.h" #include "ArduinoJson.h" +#include "MeshPacketSerializer.h" #include "NodeDB.h" #include "mesh/generated/meshtastic/mqtt.pb.h" +#include "mesh/generated/meshtastic/remote_hardware.pb.h" #include "mesh/generated/meshtastic/telemetry.pb.h" #include "modules/RoutingModule.h" #include #include -#include "mesh/generated/meshtastic/remote_hardware.pb.h" StaticJsonDocument<1024> jsonObj; StaticJsonDocument<1024> arrayObj; std::string MeshPacketSerializer::JsonSerialize(const meshtastic_MeshPacket *mp, bool shouldLog) { - // the created jsonObj is immutable after creation, so - // we need to do the heavy lifting before assembling it. - std::string msgType; - jsonObj.clear(); - arrayObj.clear(); + // the created jsonObj is immutable after creation, so + // we need to do the heavy lifting before assembling it. + std::string msgType; + jsonObj.clear(); + arrayObj.clear(); - if (mp->which_payload_variant == meshtastic_MeshPacket_decoded_tag) - { - switch (mp->decoded.portnum) - { - case meshtastic_PortNum_TEXT_MESSAGE_APP: - { - msgType = "text"; - // convert bytes to string - if (shouldLog) - LOG_DEBUG("got text message of size %u\n", mp->decoded.payload.size); + if (mp->which_payload_variant == meshtastic_MeshPacket_decoded_tag) { + switch (mp->decoded.portnum) { + case meshtastic_PortNum_TEXT_MESSAGE_APP: { + msgType = "text"; + // convert bytes to string + if (shouldLog) + LOG_DEBUG("got text message of size %u\n", mp->decoded.payload.size); - char payloadStr[(mp->decoded.payload.size) + 1]; - memcpy(payloadStr, mp->decoded.payload.bytes, mp->decoded.payload.size); - payloadStr[mp->decoded.payload.size] = 0; // null terminated string - // check if this is a JSON payload - StaticJsonDocument<512> text_doc; - DeserializationError error = deserializeJson(text_doc, payloadStr); - if (error) - { - // if it isn't, then we need to create a json object - // with the string as the value - if (shouldLog) - LOG_INFO("text message payload is of type plaintext\n"); - jsonObj["payload"]["text"] = payloadStr; - } - else - { - // if it is, then we can just use the json object - if (shouldLog) - LOG_INFO("text message payload is of type json\n"); - jsonObj["payload"] = text_doc; - } - break; - } - case meshtastic_PortNum_TELEMETRY_APP: - { - msgType = "telemetry"; - meshtastic_Telemetry scratch; - meshtastic_Telemetry *decoded = NULL; - memset(&scratch, 0, sizeof(scratch)); - 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) - { - jsonObj["payload"]["battery_level"] = (unsigned int)decoded->variant.device_metrics.battery_level; - jsonObj["payload"]["voltage"] = decoded->variant.device_metrics.voltage; - jsonObj["payload"]["channel_utilization"] = decoded->variant.device_metrics.channel_utilization; - jsonObj["payload"]["air_util_tx"] = decoded->variant.device_metrics.air_util_tx; - jsonObj["payload"]["uptime_seconds"] = (unsigned int)decoded->variant.device_metrics.uptime_seconds; - } - else if (decoded->which_variant == meshtastic_Telemetry_environment_metrics_tag) - { - jsonObj["payload"]["temperature"] = decoded->variant.environment_metrics.temperature; - jsonObj["payload"]["relative_humidity"] = decoded->variant.environment_metrics.relative_humidity; - jsonObj["payload"]["barometric_pressure"] = decoded->variant.environment_metrics.barometric_pressure; - jsonObj["payload"]["gas_resistance"] = decoded->variant.environment_metrics.gas_resistance; - jsonObj["payload"]["voltage"] = decoded->variant.environment_metrics.voltage; - jsonObj["payload"]["current"] = decoded->variant.environment_metrics.current; - jsonObj["payload"]["lux"] = decoded->variant.environment_metrics.lux; - jsonObj["payload"]["white_lux"] = decoded->variant.environment_metrics.white_lux; - jsonObj["payload"]["iaq"] = (uint)decoded->variant.environment_metrics.iaq; - jsonObj["payload"]["wind_speed"] = decoded->variant.environment_metrics.wind_speed; - jsonObj["payload"]["wind_direction"] = (uint)decoded->variant.environment_metrics.wind_direction; - jsonObj["payload"]["wind_gust"] = decoded->variant.environment_metrics.wind_gust; - jsonObj["payload"]["wind_lull"] = decoded->variant.environment_metrics.wind_lull; - } - else if (decoded->which_variant == meshtastic_Telemetry_air_quality_metrics_tag) - { - jsonObj["payload"]["pm10"] = (unsigned int)decoded->variant.air_quality_metrics.pm10_standard; - jsonObj["payload"]["pm25"] = (unsigned int)decoded->variant.air_quality_metrics.pm25_standard; - jsonObj["payload"]["pm100"] = (unsigned int)decoded->variant.air_quality_metrics.pm100_standard; - jsonObj["payload"]["pm10_e"] = (unsigned int)decoded->variant.air_quality_metrics.pm10_environmental; - jsonObj["payload"]["pm25_e"] = (unsigned int)decoded->variant.air_quality_metrics.pm25_environmental; - jsonObj["payload"]["pm100_e"] = (unsigned int)decoded->variant.air_quality_metrics.pm100_environmental; - } - else if (decoded->which_variant == meshtastic_Telemetry_power_metrics_tag) - { - jsonObj["payload"]["voltage_ch1"] = decoded->variant.power_metrics.ch1_voltage; - jsonObj["payload"]["current_ch1"] = decoded->variant.power_metrics.ch1_current; - jsonObj["payload"]["voltage_ch2"] = decoded->variant.power_metrics.ch2_voltage; - jsonObj["payload"]["current_ch2"] = decoded->variant.power_metrics.ch2_current; - jsonObj["payload"]["voltage_ch3"] = decoded->variant.power_metrics.ch3_voltage; - jsonObj["payload"]["current_ch3"] = decoded->variant.power_metrics.ch3_current; - } - } - else if (shouldLog) - { - LOG_ERROR("Error decoding protobuf for telemetry message!\n"); - return ""; - } - break; - } - case meshtastic_PortNum_NODEINFO_APP: - { - msgType = "nodeinfo"; - meshtastic_User scratch; - meshtastic_User *decoded = NULL; - memset(&scratch, 0, sizeof(scratch)); - if (pb_decode_from_bytes(mp->decoded.payload.bytes, mp->decoded.payload.size, &meshtastic_User_msg, &scratch)) - { - decoded = &scratch; - jsonObj["payload"]["id"] = decoded->id; - jsonObj["payload"]["longname"] = decoded->long_name; - jsonObj["payload"]["shortname"] = decoded->short_name; - jsonObj["payload"]["hardware"] = decoded->hw_model; - jsonObj["payload"]["role"] = (int)decoded->role; - } - else if (shouldLog) - { - LOG_ERROR("Error decoding protobuf for nodeinfo message!\n"); - return ""; - } - break; - } - case meshtastic_PortNum_POSITION_APP: - { - msgType = "position"; - meshtastic_Position scratch; - meshtastic_Position *decoded = NULL; - memset(&scratch, 0, sizeof(scratch)); - if (pb_decode_from_bytes(mp->decoded.payload.bytes, mp->decoded.payload.size, &meshtastic_Position_msg, &scratch)) - { - decoded = &scratch; - if ((int)decoded->time) - { - jsonObj["payload"]["time"] = (unsigned int)decoded->time; - } - if ((int)decoded->timestamp) - { - jsonObj["payload"]["timestamp"] = (unsigned int)decoded->timestamp; - } - jsonObj["payload"]["latitude_i"] = (int)decoded->latitude_i; - jsonObj["payload"]["longitude_i"] = (int)decoded->longitude_i; - if ((int)decoded->altitude) - { - jsonObj["payload"]["altitude"] = (int)decoded->altitude; - } - if ((int)decoded->ground_speed) - { - jsonObj["payload"]["ground_speed"] = (unsigned int)decoded->ground_speed; - } - if (int(decoded->ground_track)) - { - jsonObj["payload"]["ground_track"] = (unsigned int)decoded->ground_track; - } - if (int(decoded->sats_in_view)) - { - jsonObj["payload"]["sats_in_view"] = (unsigned int)decoded->sats_in_view; - } - if ((int)decoded->PDOP) - { - jsonObj["payload"]["PDOP"] = (int)decoded->PDOP; - } - if ((int)decoded->HDOP) - { - jsonObj["payload"]["HDOP"] = (int)decoded->HDOP; - } - if ((int)decoded->VDOP) - { - jsonObj["payload"]["VDOP"] = (int)decoded->VDOP; - } - if ((int)decoded->precision_bits) - { - jsonObj["payload"]["precision_bits"] = (int)decoded->precision_bits; - } - } - else if (shouldLog) - { - LOG_ERROR("Error decoding protobuf for position message!\n"); - return ""; - } - break; - } - case meshtastic_PortNum_WAYPOINT_APP: - { - msgType = "position"; - meshtastic_Waypoint scratch; - meshtastic_Waypoint *decoded = NULL; - memset(&scratch, 0, sizeof(scratch)); - if (pb_decode_from_bytes(mp->decoded.payload.bytes, mp->decoded.payload.size, &meshtastic_Waypoint_msg, &scratch)) - { - decoded = &scratch; - jsonObj["payload"]["id"] = (unsigned int)decoded->id; - jsonObj["payload"]["name"] = decoded->name; - jsonObj["payload"]["description"] = decoded->description; - jsonObj["payload"]["expire"] = (unsigned int)decoded->expire; - jsonObj["payload"]["locked_to"] = (unsigned int)decoded->locked_to; - jsonObj["payload"]["latitude_i"] = (int)decoded->latitude_i; - jsonObj["payload"]["longitude_i"] = (int)decoded->longitude_i; - } - else if (shouldLog) - { - LOG_ERROR("Error decoding protobuf for position message!\n"); - return ""; - } - break; - } - case meshtastic_PortNum_NEIGHBORINFO_APP: - { - msgType = "neighborinfo"; - meshtastic_NeighborInfo scratch; - meshtastic_NeighborInfo *decoded = NULL; - memset(&scratch, 0, sizeof(scratch)); - if (pb_decode_from_bytes(mp->decoded.payload.bytes, mp->decoded.payload.size, &meshtastic_NeighborInfo_msg, - &scratch)) - { - decoded = &scratch; - jsonObj["payload"]["node_id"] = (unsigned int)decoded->node_id; - jsonObj["payload"]["node_broadcast_interval_secs"] = (unsigned int)decoded->node_broadcast_interval_secs; - jsonObj["payload"]["last_sent_by_id"] = (unsigned int)decoded->last_sent_by_id; - jsonObj["payload"]["neighbors_count"] = decoded->neighbors_count; + char payloadStr[(mp->decoded.payload.size) + 1]; + memcpy(payloadStr, mp->decoded.payload.bytes, mp->decoded.payload.size); + payloadStr[mp->decoded.payload.size] = 0; // null terminated string + // check if this is a JSON payload + StaticJsonDocument<512> text_doc; + DeserializationError error = deserializeJson(text_doc, payloadStr); + if (error) { + // if it isn't, then we need to create a json object + // with the string as the value + if (shouldLog) + LOG_INFO("text message payload is of type plaintext\n"); + jsonObj["payload"]["text"] = payloadStr; + } else { + // if it is, then we can just use the json object + if (shouldLog) + LOG_INFO("text message payload is of type json\n"); + jsonObj["payload"] = text_doc; + } + break; + } + case meshtastic_PortNum_TELEMETRY_APP: { + msgType = "telemetry"; + meshtastic_Telemetry scratch; + meshtastic_Telemetry *decoded = NULL; + memset(&scratch, 0, sizeof(scratch)); + 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) { + jsonObj["payload"]["battery_level"] = (unsigned int)decoded->variant.device_metrics.battery_level; + jsonObj["payload"]["voltage"] = decoded->variant.device_metrics.voltage; + jsonObj["payload"]["channel_utilization"] = decoded->variant.device_metrics.channel_utilization; + jsonObj["payload"]["air_util_tx"] = decoded->variant.device_metrics.air_util_tx; + jsonObj["payload"]["uptime_seconds"] = (unsigned int)decoded->variant.device_metrics.uptime_seconds; + } else if (decoded->which_variant == meshtastic_Telemetry_environment_metrics_tag) { + jsonObj["payload"]["temperature"] = decoded->variant.environment_metrics.temperature; + jsonObj["payload"]["relative_humidity"] = decoded->variant.environment_metrics.relative_humidity; + jsonObj["payload"]["barometric_pressure"] = decoded->variant.environment_metrics.barometric_pressure; + jsonObj["payload"]["gas_resistance"] = decoded->variant.environment_metrics.gas_resistance; + jsonObj["payload"]["voltage"] = decoded->variant.environment_metrics.voltage; + jsonObj["payload"]["current"] = decoded->variant.environment_metrics.current; + jsonObj["payload"]["lux"] = decoded->variant.environment_metrics.lux; + jsonObj["payload"]["white_lux"] = decoded->variant.environment_metrics.white_lux; + jsonObj["payload"]["iaq"] = (uint)decoded->variant.environment_metrics.iaq; + jsonObj["payload"]["wind_speed"] = decoded->variant.environment_metrics.wind_speed; + jsonObj["payload"]["wind_direction"] = (uint)decoded->variant.environment_metrics.wind_direction; + jsonObj["payload"]["wind_gust"] = decoded->variant.environment_metrics.wind_gust; + jsonObj["payload"]["wind_lull"] = decoded->variant.environment_metrics.wind_lull; + } else if (decoded->which_variant == meshtastic_Telemetry_air_quality_metrics_tag) { + jsonObj["payload"]["pm10"] = (unsigned int)decoded->variant.air_quality_metrics.pm10_standard; + jsonObj["payload"]["pm25"] = (unsigned int)decoded->variant.air_quality_metrics.pm25_standard; + jsonObj["payload"]["pm100"] = (unsigned int)decoded->variant.air_quality_metrics.pm100_standard; + jsonObj["payload"]["pm10_e"] = (unsigned int)decoded->variant.air_quality_metrics.pm10_environmental; + jsonObj["payload"]["pm25_e"] = (unsigned int)decoded->variant.air_quality_metrics.pm25_environmental; + jsonObj["payload"]["pm100_e"] = (unsigned int)decoded->variant.air_quality_metrics.pm100_environmental; + } else if (decoded->which_variant == meshtastic_Telemetry_power_metrics_tag) { + jsonObj["payload"]["voltage_ch1"] = decoded->variant.power_metrics.ch1_voltage; + jsonObj["payload"]["current_ch1"] = decoded->variant.power_metrics.ch1_current; + jsonObj["payload"]["voltage_ch2"] = decoded->variant.power_metrics.ch2_voltage; + jsonObj["payload"]["current_ch2"] = decoded->variant.power_metrics.ch2_current; + jsonObj["payload"]["voltage_ch3"] = decoded->variant.power_metrics.ch3_voltage; + jsonObj["payload"]["current_ch3"] = decoded->variant.power_metrics.ch3_current; + } + } else if (shouldLog) { + LOG_ERROR("Error decoding protobuf for telemetry message!\n"); + return ""; + } + break; + } + case meshtastic_PortNum_NODEINFO_APP: { + msgType = "nodeinfo"; + meshtastic_User scratch; + meshtastic_User *decoded = NULL; + memset(&scratch, 0, sizeof(scratch)); + if (pb_decode_from_bytes(mp->decoded.payload.bytes, mp->decoded.payload.size, &meshtastic_User_msg, &scratch)) { + decoded = &scratch; + jsonObj["payload"]["id"] = decoded->id; + jsonObj["payload"]["longname"] = decoded->long_name; + jsonObj["payload"]["shortname"] = decoded->short_name; + jsonObj["payload"]["hardware"] = decoded->hw_model; + jsonObj["payload"]["role"] = (int)decoded->role; + } else if (shouldLog) { + LOG_ERROR("Error decoding protobuf for nodeinfo message!\n"); + return ""; + } + break; + } + case meshtastic_PortNum_POSITION_APP: { + msgType = "position"; + meshtastic_Position scratch; + meshtastic_Position *decoded = NULL; + memset(&scratch, 0, sizeof(scratch)); + if (pb_decode_from_bytes(mp->decoded.payload.bytes, mp->decoded.payload.size, &meshtastic_Position_msg, &scratch)) { + decoded = &scratch; + if ((int)decoded->time) { + jsonObj["payload"]["time"] = (unsigned int)decoded->time; + } + if ((int)decoded->timestamp) { + jsonObj["payload"]["timestamp"] = (unsigned int)decoded->timestamp; + } + jsonObj["payload"]["latitude_i"] = (int)decoded->latitude_i; + jsonObj["payload"]["longitude_i"] = (int)decoded->longitude_i; + if ((int)decoded->altitude) { + jsonObj["payload"]["altitude"] = (int)decoded->altitude; + } + if ((int)decoded->ground_speed) { + jsonObj["payload"]["ground_speed"] = (unsigned int)decoded->ground_speed; + } + if (int(decoded->ground_track)) { + jsonObj["payload"]["ground_track"] = (unsigned int)decoded->ground_track; + } + if (int(decoded->sats_in_view)) { + jsonObj["payload"]["sats_in_view"] = (unsigned int)decoded->sats_in_view; + } + if ((int)decoded->PDOP) { + jsonObj["payload"]["PDOP"] = (int)decoded->PDOP; + } + if ((int)decoded->HDOP) { + jsonObj["payload"]["HDOP"] = (int)decoded->HDOP; + } + if ((int)decoded->VDOP) { + jsonObj["payload"]["VDOP"] = (int)decoded->VDOP; + } + if ((int)decoded->precision_bits) { + jsonObj["payload"]["precision_bits"] = (int)decoded->precision_bits; + } + } else if (shouldLog) { + LOG_ERROR("Error decoding protobuf for position message!\n"); + return ""; + } + break; + } + case meshtastic_PortNum_WAYPOINT_APP: { + msgType = "position"; + meshtastic_Waypoint scratch; + meshtastic_Waypoint *decoded = NULL; + memset(&scratch, 0, sizeof(scratch)); + if (pb_decode_from_bytes(mp->decoded.payload.bytes, mp->decoded.payload.size, &meshtastic_Waypoint_msg, &scratch)) { + decoded = &scratch; + jsonObj["payload"]["id"] = (unsigned int)decoded->id; + jsonObj["payload"]["name"] = decoded->name; + jsonObj["payload"]["description"] = decoded->description; + jsonObj["payload"]["expire"] = (unsigned int)decoded->expire; + jsonObj["payload"]["locked_to"] = (unsigned int)decoded->locked_to; + jsonObj["payload"]["latitude_i"] = (int)decoded->latitude_i; + jsonObj["payload"]["longitude_i"] = (int)decoded->longitude_i; + } else if (shouldLog) { + LOG_ERROR("Error decoding protobuf for position message!\n"); + return ""; + } + break; + } + case meshtastic_PortNum_NEIGHBORINFO_APP: { + msgType = "neighborinfo"; + meshtastic_NeighborInfo scratch; + meshtastic_NeighborInfo *decoded = NULL; + memset(&scratch, 0, sizeof(scratch)); + if (pb_decode_from_bytes(mp->decoded.payload.bytes, mp->decoded.payload.size, &meshtastic_NeighborInfo_msg, + &scratch)) { + decoded = &scratch; + jsonObj["payload"]["node_id"] = (unsigned int)decoded->node_id; + jsonObj["payload"]["node_broadcast_interval_secs"] = (unsigned int)decoded->node_broadcast_interval_secs; + jsonObj["payload"]["last_sent_by_id"] = (unsigned int)decoded->last_sent_by_id; + jsonObj["payload"]["neighbors_count"] = decoded->neighbors_count; - JsonObject neighbors_obj = arrayObj.to(); - JsonArray neighbors = neighbors_obj.createNestedArray("neighbors"); - JsonObject neighbors_0 = neighbors.createNestedObject(); + JsonObject neighbors_obj = arrayObj.to(); + JsonArray neighbors = neighbors_obj.createNestedArray("neighbors"); + JsonObject neighbors_0 = neighbors.createNestedObject(); - for (uint8_t i = 0; i < decoded->neighbors_count; i++) - { - neighbors_0["node_id"] = (unsigned int)decoded->neighbors[i].node_id; - neighbors_0["snr"] = (int)decoded->neighbors[i].snr; - neighbors[i + 1] = neighbors_0; - neighbors_0.clear(); - } - neighbors.remove(0); - jsonObj["payload"]["neighbors"] = neighbors; - } - else if (shouldLog) - { - LOG_ERROR("Error decoding protobuf for neighborinfo message!\n"); - return ""; - } - break; - } - case meshtastic_PortNum_TRACEROUTE_APP: - { - if (mp->decoded.request_id) - { // Only report the traceroute response - msgType = "traceroute"; - meshtastic_RouteDiscovery scratch; - meshtastic_RouteDiscovery *decoded = NULL; - memset(&scratch, 0, sizeof(scratch)); - if (pb_decode_from_bytes(mp->decoded.payload.bytes, mp->decoded.payload.size, &meshtastic_RouteDiscovery_msg, - &scratch)) - { - decoded = &scratch; - JsonArray route = arrayObj.createNestedArray("route"); + for (uint8_t i = 0; i < decoded->neighbors_count; i++) { + neighbors_0["node_id"] = (unsigned int)decoded->neighbors[i].node_id; + neighbors_0["snr"] = (int)decoded->neighbors[i].snr; + neighbors[i + 1] = neighbors_0; + neighbors_0.clear(); + } + neighbors.remove(0); + jsonObj["payload"]["neighbors"] = neighbors; + } else if (shouldLog) { + LOG_ERROR("Error decoding protobuf for neighborinfo message!\n"); + return ""; + } + break; + } + case meshtastic_PortNum_TRACEROUTE_APP: { + if (mp->decoded.request_id) { // Only report the traceroute response + msgType = "traceroute"; + meshtastic_RouteDiscovery scratch; + meshtastic_RouteDiscovery *decoded = NULL; + memset(&scratch, 0, sizeof(scratch)); + if (pb_decode_from_bytes(mp->decoded.payload.bytes, mp->decoded.payload.size, &meshtastic_RouteDiscovery_msg, + &scratch)) { + decoded = &scratch; + JsonArray route = arrayObj.createNestedArray("route"); - auto addToRoute = [](JsonArray *route, NodeNum num) - { - char long_name[40] = "Unknown"; - meshtastic_NodeInfoLite *node = nodeDB->getMeshNode(num); - bool name_known = node ? node->has_user : false; - if (name_known) - memcpy(long_name, node->user.long_name, sizeof(long_name)); - route->add(long_name); - }; + auto addToRoute = [](JsonArray *route, NodeNum num) { + char long_name[40] = "Unknown"; + meshtastic_NodeInfoLite *node = nodeDB->getMeshNode(num); + bool name_known = node ? node->has_user : false; + if (name_known) + memcpy(long_name, node->user.long_name, sizeof(long_name)); + route->add(long_name); + }; - addToRoute(&route, mp->to); // route.add(mp->to); - for (uint8_t i = 0; i < decoded->route_count; i++) - { - addToRoute(&route, decoded->route[i]); // route.add(decoded->route[i]); - } - addToRoute(&route, mp->from); // route.add(mp->from); // Ended at the original destination (source of response) + addToRoute(&route, mp->to); // route.add(mp->to); + for (uint8_t i = 0; i < decoded->route_count; i++) { + addToRoute(&route, decoded->route[i]); // route.add(decoded->route[i]); + } + addToRoute(&route, + mp->from); // route.add(mp->from); // Ended at the original destination (source of response) - jsonObj["payload"]["route"] = route; - } - else if (shouldLog) - { - LOG_ERROR("Error decoding protobuf for traceroute message!\n"); - return ""; - } - } - else - { - LOG_WARN("Traceroute response not reported"); - return ""; - } - break; - } - case meshtastic_PortNum_DETECTION_SENSOR_APP: - { - msgType = "detection"; - char payloadStr[(mp->decoded.payload.size) + 1]; - memcpy(payloadStr, mp->decoded.payload.bytes, mp->decoded.payload.size); - payloadStr[mp->decoded.payload.size] = 0; // null terminated string - jsonObj["payload"]["text"] = payloadStr; - break; - } - case meshtastic_PortNum_REMOTE_HARDWARE_APP: - { - meshtastic_HardwareMessage scratch; - meshtastic_HardwareMessage *decoded = NULL; - memset(&scratch, 0, sizeof(scratch)); - if (pb_decode_from_bytes(mp->decoded.payload.bytes, mp->decoded.payload.size, &meshtastic_HardwareMessage_msg, - &scratch)) - { - decoded = &scratch; - if (decoded->type == meshtastic_HardwareMessage_Type_GPIOS_CHANGED) - { - msgType = "gpios_changed"; - jsonObj["payload"]["gpio_value"] = (unsigned int)decoded->gpio_value; - } - else if (decoded->type == meshtastic_HardwareMessage_Type_READ_GPIOS_REPLY) - { - msgType = "gpios_read_reply"; - jsonObj["payload"]["gpio_value"] = (unsigned int)decoded->gpio_value; - jsonObj["payload"]["gpio_mask"] = (unsigned int)decoded->gpio_mask; - } - } - else if (shouldLog) - { - LOG_ERROR("Error decoding protobuf for RemoteHardware message!\n"); - return ""; - } - break; - } - // add more packet types here if needed - default: - LOG_WARN("Unsupported packet type %d\n", mp->decoded.portnum); - return ""; - break; - } - } - else if (shouldLog) - { - LOG_WARN("Couldn't convert encrypted payload of MeshPacket to JSON\n"); - return ""; - } + jsonObj["payload"]["route"] = route; + } else if (shouldLog) { + LOG_ERROR("Error decoding protobuf for traceroute message!\n"); + return ""; + } + } else { + LOG_WARN("Traceroute response not reported"); + return ""; + } + break; + } + case meshtastic_PortNum_DETECTION_SENSOR_APP: { + msgType = "detection"; + char payloadStr[(mp->decoded.payload.size) + 1]; + memcpy(payloadStr, mp->decoded.payload.bytes, mp->decoded.payload.size); + payloadStr[mp->decoded.payload.size] = 0; // null terminated string + jsonObj["payload"]["text"] = payloadStr; + break; + } + case meshtastic_PortNum_REMOTE_HARDWARE_APP: { + meshtastic_HardwareMessage scratch; + meshtastic_HardwareMessage *decoded = NULL; + memset(&scratch, 0, sizeof(scratch)); + if (pb_decode_from_bytes(mp->decoded.payload.bytes, mp->decoded.payload.size, &meshtastic_HardwareMessage_msg, + &scratch)) { + decoded = &scratch; + if (decoded->type == meshtastic_HardwareMessage_Type_GPIOS_CHANGED) { + msgType = "gpios_changed"; + jsonObj["payload"]["gpio_value"] = (unsigned int)decoded->gpio_value; + } else if (decoded->type == meshtastic_HardwareMessage_Type_READ_GPIOS_REPLY) { + msgType = "gpios_read_reply"; + jsonObj["payload"]["gpio_value"] = (unsigned int)decoded->gpio_value; + jsonObj["payload"]["gpio_mask"] = (unsigned int)decoded->gpio_mask; + } + } else if (shouldLog) { + LOG_ERROR("Error decoding protobuf for RemoteHardware message!\n"); + return ""; + } + break; + } + // add more packet types here if needed + default: + LOG_WARN("Unsupported packet type %d\n", mp->decoded.portnum); + return ""; + break; + } + } else if (shouldLog) { + LOG_WARN("Couldn't convert encrypted payload of MeshPacket to JSON\n"); + return ""; + } - jsonObj["id"] = (unsigned int)mp->id; - jsonObj["timestamp"] = (unsigned int)mp->rx_time; - jsonObj["to"] = (unsigned int)mp->to; - jsonObj["from"] = (unsigned int)mp->from; - jsonObj["channel"] = (unsigned int)mp->channel; - jsonObj["type"] = msgType.c_str(); - jsonObj["sender"] = owner.id; - if (mp->rx_rssi != 0) - jsonObj["rssi"] = (int)mp->rx_rssi; - if (mp->rx_snr != 0) - jsonObj["snr"] = (float)mp->rx_snr; - if (mp->hop_start != 0 && mp->hop_limit <= mp->hop_start) - { - jsonObj["hops_away"] = (unsigned int)(mp->hop_start - mp->hop_limit); - jsonObj["hop_start"] = (unsigned int)(mp->hop_start); - } + jsonObj["id"] = (unsigned int)mp->id; + jsonObj["timestamp"] = (unsigned int)mp->rx_time; + jsonObj["to"] = (unsigned int)mp->to; + jsonObj["from"] = (unsigned int)mp->from; + jsonObj["channel"] = (unsigned int)mp->channel; + jsonObj["type"] = msgType.c_str(); + jsonObj["sender"] = owner.id; + if (mp->rx_rssi != 0) + jsonObj["rssi"] = (int)mp->rx_rssi; + if (mp->rx_snr != 0) + jsonObj["snr"] = (float)mp->rx_snr; + if (mp->hop_start != 0 && mp->hop_limit <= mp->hop_start) { + jsonObj["hops_away"] = (unsigned int)(mp->hop_start - mp->hop_limit); + jsonObj["hop_start"] = (unsigned int)(mp->hop_start); + } - // serialize and write it to the stream + // serialize and write it to the stream - // Serial.printf("serialized json message: \r\n"); - // serializeJson(jsonObj, Serial); - // Serial.println(""); + // Serial.printf("serialized json message: \r\n"); + // serializeJson(jsonObj, Serial); + // Serial.println(""); - std::string jsonStr = ""; - serializeJson(jsonObj, jsonStr); + std::string jsonStr = ""; + serializeJson(jsonObj, jsonStr); - if (shouldLog) - LOG_INFO("serialized json message: %s\n", jsonStr.c_str()); + if (shouldLog) + LOG_INFO("serialized json message: %s\n", jsonStr.c_str()); - return jsonStr; + return jsonStr; } std::string MeshPacketSerializer::JsonSerializeEncrypted(const meshtastic_MeshPacket *mp) { - jsonObj.clear(); - jsonObj["id"] = (unsigned int)mp->id; - jsonObj["time_ms"] = (double)millis(); - jsonObj["timestamp"] = (unsigned int)mp->rx_time; - jsonObj["to"] = (unsigned int)mp->to; - jsonObj["from"] = (unsigned int)mp->from; - jsonObj["channel"] = (unsigned int)mp->channel; - jsonObj["want_ack"] = mp->want_ack; + jsonObj.clear(); + jsonObj["id"] = (unsigned int)mp->id; + jsonObj["time_ms"] = (double)millis(); + jsonObj["timestamp"] = (unsigned int)mp->rx_time; + jsonObj["to"] = (unsigned int)mp->to; + jsonObj["from"] = (unsigned int)mp->from; + jsonObj["channel"] = (unsigned int)mp->channel; + jsonObj["want_ack"] = mp->want_ack; - if (mp->rx_rssi != 0) - jsonObj["rssi"] = (int)mp->rx_rssi; - if (mp->rx_snr != 0) - jsonObj["snr"] = (float)mp->rx_snr; - if (mp->hop_start != 0 && mp->hop_limit <= mp->hop_start) - { - jsonObj["hops_away"] = (unsigned int)(mp->hop_start - mp->hop_limit); - jsonObj["hop_start"] = (unsigned int)(mp->hop_start); - } - jsonObj["size"] = (unsigned int)mp->encrypted.size; - auto encryptedStr = bytesToHex(mp->encrypted.bytes, mp->encrypted.size); - jsonObj["bytes"] = encryptedStr.c_str(); + if (mp->rx_rssi != 0) + jsonObj["rssi"] = (int)mp->rx_rssi; + if (mp->rx_snr != 0) + jsonObj["snr"] = (float)mp->rx_snr; + if (mp->hop_start != 0 && mp->hop_limit <= mp->hop_start) { + jsonObj["hops_away"] = (unsigned int)(mp->hop_start - mp->hop_limit); + jsonObj["hop_start"] = (unsigned int)(mp->hop_start); + } + jsonObj["size"] = (unsigned int)mp->encrypted.size; + auto encryptedStr = bytesToHex(mp->encrypted.bytes, mp->encrypted.size); + jsonObj["bytes"] = encryptedStr.c_str(); - // serialize and write it to the stream - std::string jsonStr = ""; - serializeJson(jsonObj, jsonStr); + // serialize and write it to the stream + std::string jsonStr = ""; + serializeJson(jsonObj, jsonStr); - return jsonStr; + return jsonStr; } #endif \ No newline at end of file From cd480846e93efc2d06da8f84a5028082bbd093ac Mon Sep 17 00:00:00 2001 From: GUVWAF Date: Thu, 12 Sep 2024 19:52:36 +0200 Subject: [PATCH 11/88] Remove accelerometer lib --- platformio.ini | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/platformio.ini b/platformio.ini index 1847bd113..167d8710b 100644 --- a/platformio.ini +++ b/platformio.ini @@ -161,5 +161,4 @@ lib_deps = mprograms/QMC5883LCompass@^1.2.0 - https://github.com/meshtastic/DFRobot_LarkWeatherStation#dee914270dc7cb3e43fbf034edd85a63a16a12ee - https://github.com/gjelsoe/STK8xxx-Accelerometer.git#v0.1.1 \ No newline at end of file + https://github.com/meshtastic/DFRobot_LarkWeatherStation#dee914270dc7cb3e43fbf034edd85a63a16a12ee \ No newline at end of file From fa29386eb766dfc33308d3c86893e8a0e739d28f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Sun, 29 Sep 2024 12:40:17 +0200 Subject: [PATCH 12/88] Update main_matrix.yml --- .github/workflows/main_matrix.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/main_matrix.yml b/.github/workflows/main_matrix.yml index 68f7bb31c..bb2f43503 100644 --- a/.github/workflows/main_matrix.yml +++ b/.github/workflows/main_matrix.yml @@ -35,7 +35,7 @@ jobs: name: Checkout base - id: jsonStep run: | - if [[ "${{ github.ref }}" == "refs/heads/master" ]]; then + if [[ "${{ github.ref_name }}" == "master" ]]; then TARGETS=$(./bin/generate_ci_matrix.py ${{matrix.arch}}) else TARGETS=$(./bin/generate_ci_matrix.py ${{matrix.arch}} quick) From ef2035a60c5e92159e87eb0258eb99f1bdc4f607 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Sun, 29 Sep 2024 13:52:47 +0200 Subject: [PATCH 13/88] runner debug --- .github/workflows/main_matrix.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/main_matrix.yml b/.github/workflows/main_matrix.yml index bb2f43503..2daaeea24 100644 --- a/.github/workflows/main_matrix.yml +++ b/.github/workflows/main_matrix.yml @@ -40,7 +40,7 @@ jobs: else TARGETS=$(./bin/generate_ci_matrix.py ${{matrix.arch}} quick) fi - echo "$TARGETS" + echo "${{ github.ref_name }} ${{ github.base_ref }} ${{ github.head_ref }} ${{ github.ref }} $TARGETS" echo "${{matrix.arch}}=$(jq -cn --argjson environments "$TARGETS" '{board: $environments}')" >> $GITHUB_OUTPUT outputs: esp32: ${{ steps.jsonStep.outputs.esp32 }} From d0440f3cac06d5c8f91f7a622cce320925044f3e Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Sun, 29 Sep 2024 13:54:46 +0200 Subject: [PATCH 14/88] don't interfere with the trunk check --- .github/workflows/main_matrix.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/main_matrix.yml b/.github/workflows/main_matrix.yml index bb2f43503..4c1493ae4 100644 --- a/.github/workflows/main_matrix.yml +++ b/.github/workflows/main_matrix.yml @@ -1,6 +1,6 @@ name: CI concurrency: - group: ${{ github.head_ref || github.run_id }} + group: ci-${{ github.head_ref || github.run_id }} cancel-in-progress: true #concurrency: # group: ${{ github.ref }} From 42a330118847213f7116c0b4047bbbb608aadb97 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Sun, 29 Sep 2024 13:58:07 +0200 Subject: [PATCH 15/88] Update main_matrix.yml --- .github/workflows/main_matrix.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/main_matrix.yml b/.github/workflows/main_matrix.yml index 62f215811..29602600a 100644 --- a/.github/workflows/main_matrix.yml +++ b/.github/workflows/main_matrix.yml @@ -40,7 +40,7 @@ jobs: else TARGETS=$(./bin/generate_ci_matrix.py ${{matrix.arch}} quick) fi - echo "${{ github.ref_name }} ${{ github.base_ref }} ${{ github.head_ref }} ${{ github.ref }} $TARGETS" + echo "Name: ${{ github.ref_name }} Base: ${{ github.base_ref }} Head: ${{ github.head_ref }} Ref: ${{ github.ref }} $TARGETS" echo "${{matrix.arch}}=$(jq -cn --argjson environments "$TARGETS" '{board: $environments}')" >> $GITHUB_OUTPUT outputs: esp32: ${{ steps.jsonStep.outputs.esp32 }} From 88af23319ca80b3988c7cc588d23be90628de0ce Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Sun, 29 Sep 2024 14:00:36 +0200 Subject: [PATCH 16/88] Aha! --- .github/workflows/main_matrix.yml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/workflows/main_matrix.yml b/.github/workflows/main_matrix.yml index 29602600a..529de3de5 100644 --- a/.github/workflows/main_matrix.yml +++ b/.github/workflows/main_matrix.yml @@ -35,12 +35,12 @@ jobs: name: Checkout base - id: jsonStep run: | - if [[ "${{ github.ref_name }}" == "master" ]]; then + if [[ "${{ github.head_ref }}" == "refs/heads/master" ]]; then TARGETS=$(./bin/generate_ci_matrix.py ${{matrix.arch}}) else TARGETS=$(./bin/generate_ci_matrix.py ${{matrix.arch}} quick) fi - echo "Name: ${{ github.ref_name }} Base: ${{ github.base_ref }} Head: ${{ github.head_ref }} Ref: ${{ github.ref }} $TARGETS" + echo "Name: ${{ github.ref_name }} Base: ${{ github.base_ref }} Head: ${{ github.head_ref }} Ref: ${{ github.ref }} Targets: $TARGETS" echo "${{matrix.arch}}=$(jq -cn --argjson environments "$TARGETS" '{board: $environments}')" >> $GITHUB_OUTPUT outputs: esp32: ${{ steps.jsonStep.outputs.esp32 }} From 2e935fd9430b9f1cefed04784e908b42b5a67f05 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Sun, 29 Sep 2024 14:03:22 +0200 Subject: [PATCH 17/88] why is this different than github docs? --- .github/workflows/main_matrix.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/main_matrix.yml b/.github/workflows/main_matrix.yml index 529de3de5..b79b41d52 100644 --- a/.github/workflows/main_matrix.yml +++ b/.github/workflows/main_matrix.yml @@ -35,7 +35,7 @@ jobs: name: Checkout base - id: jsonStep run: | - if [[ "${{ github.head_ref }}" == "refs/heads/master" ]]; then + if [[ "${{ github.head_ref }}" == "master" ]]; then TARGETS=$(./bin/generate_ci_matrix.py ${{matrix.arch}}) else TARGETS=$(./bin/generate_ci_matrix.py ${{matrix.arch}} quick) From dcb2707d94d535cbca44abda71e941f9d5c03b17 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Sun, 29 Sep 2024 07:28:20 -0500 Subject: [PATCH 18/88] Return queue status on rate limit throttling (#4901) --- src/mesh/PhoneAPI.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/src/mesh/PhoneAPI.cpp b/src/mesh/PhoneAPI.cpp index ecc5effe9..ad4a1f33d 100644 --- a/src/mesh/PhoneAPI.cpp +++ b/src/mesh/PhoneAPI.cpp @@ -605,10 +605,14 @@ bool PhoneAPI::handleToRadioPacket(meshtastic_MeshPacket &p) Throttle::isWithinTimespanMs(lastPortNumToRadio[p.decoded.portnum], THIRTY_SECONDS_MS)) { LOG_WARN("Rate limiting portnum %d\n", p.decoded.portnum); sendNotification(meshtastic_LogRecord_Level_WARNING, p.id, "TraceRoute can only be sent once every 30 seconds"); + meshtastic_QueueStatus qs = router->getQueueStatus(); + service->sendQueueStatusToPhone(qs, 0, p.id); return false; } else if (p.decoded.portnum == meshtastic_PortNum_POSITION_APP && lastPortNumToRadio[p.decoded.portnum] && Throttle::isWithinTimespanMs(lastPortNumToRadio[p.decoded.portnum], FIVE_SECONDS_MS)) { LOG_WARN("Rate limiting portnum %d\n", p.decoded.portnum); + meshtastic_QueueStatus qs = router->getQueueStatus(); + service->sendQueueStatusToPhone(qs, 0, p.id); // FIXME: Figure out why this continues to happen // sendNotification(meshtastic_LogRecord_Level_WARNING, p.id, "Position can only be sent once every 5 seconds"); return false; From 403e5c304ecf22ed084b341c203147d5be2400c9 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Sun, 29 Sep 2024 07:29:53 -0500 Subject: [PATCH 19/88] Fix: Not being able to stop Ext. Notification nagging for screenless devices (#4899) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * Move logic up to button thread for screen-less devices * Comment doesn't apply * Fiddy --------- Co-authored-by: Thomas Göttgens --- src/ButtonThread.cpp | 5 +++++ src/graphics/Screen.cpp | 8 +------- 2 files changed, 6 insertions(+), 7 deletions(-) diff --git a/src/ButtonThread.cpp b/src/ButtonThread.cpp index 5351fa049..9e6ef55f5 100644 --- a/src/ButtonThread.cpp +++ b/src/ButtonThread.cpp @@ -124,6 +124,11 @@ int32_t ButtonThread::runOnce() switch (btnEvent) { case BUTTON_EVENT_PRESSED: { LOG_BUTTON("press!\n"); + // If a nag notification is running, stop it and prevent other actions + if (moduleConfig.external_notification.enabled && (externalNotificationModule->nagCycleCutoff != UINT32_MAX)) { + externalNotificationModule->stopNow(); + return 50; + } #ifdef BUTTON_PIN if (((config.device.button_gpio ? config.device.button_gpio : BUTTON_PIN) != moduleConfig.canned_message.inputbroker_pin_press) || diff --git a/src/graphics/Screen.cpp b/src/graphics/Screen.cpp index 4f6a5a45f..ef6b05ca4 100644 --- a/src/graphics/Screen.cpp +++ b/src/graphics/Screen.cpp @@ -1884,13 +1884,7 @@ int32_t Screen::runOnce() handleSetOn(false); break; case Cmd::ON_PRESS: - // If a nag notification is running, stop it - if (moduleConfig.external_notification.enabled && (externalNotificationModule->nagCycleCutoff != UINT32_MAX)) { - externalNotificationModule->stopNow(); - } else { - // Don't advance the screen if we just wanted to switch off the nag notification - handleOnPress(); - } + handleOnPress(); break; case Cmd::SHOW_PREV_FRAME: handleShowPrevFrame(); From d41d4c930e9b8af4f3045d3b32702a8278c988f3 Mon Sep 17 00:00:00 2001 From: dahanc Date: Sun, 29 Sep 2024 07:30:10 -0500 Subject: [PATCH 20/88] =?UTF-8?q?When=20importing=20config,=20keep=20Bluet?= =?UTF-8?q?ooth=20on=20and=20defer=20rebooting=20until=20co=E2=80=A6=20(#4?= =?UTF-8?q?898)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * When importing config, keep Bluetooth on and defer rebooting until config is committed * One more place that was prematurely disabling Bluetooth --------- Co-authored-by: Ben Meadors --- src/modules/AdminModule.cpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/src/modules/AdminModule.cpp b/src/modules/AdminModule.cpp index 09311abda..8c354b6c8 100644 --- a/src/modules/AdminModule.cpp +++ b/src/modules/AdminModule.cpp @@ -583,7 +583,7 @@ void AdminModule::handleSetConfig(const meshtastic_Config &c) break; } - if (requiresReboot) { + if (requiresReboot && !hasOpenEditTransaction) { disableBluetooth(); } @@ -592,7 +592,8 @@ void AdminModule::handleSetConfig(const meshtastic_Config &c) void AdminModule::handleSetModuleConfig(const meshtastic_ModuleConfig &c) { - disableBluetooth(); + if (!hasOpenEditTransaction) + disableBluetooth(); switch (c.which_payload_variant) { case meshtastic_ModuleConfig_mqtt_tag: LOG_INFO("Setting module config: MQTT\n"); @@ -966,7 +967,7 @@ void AdminModule::saveChanges(int saveWhat, bool shouldReboot) } else { LOG_INFO("Delaying save of changes to disk until the open transaction is committed\n"); } - if (shouldReboot) { + if (shouldReboot && !hasOpenEditTransaction) { reboot(DEFAULT_REBOOT_SECONDS); } } From d73cbf14d5b0cf8a3f94d8028b9ab60d297fed96 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Michael=20Gjels=C3=B8?= <36234524+gjelsoe@users.noreply.github.com> Date: Sun, 29 Sep 2024 18:49:16 +0200 Subject: [PATCH 21/88] Get accelerometerThread running from AdminModule. (#4886) --- src/modules/AdminModule.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/src/modules/AdminModule.cpp b/src/modules/AdminModule.cpp index 8c354b6c8..4a7af4817 100644 --- a/src/modules/AdminModule.cpp +++ b/src/modules/AdminModule.cpp @@ -432,6 +432,8 @@ void AdminModule::handleSetConfig(const meshtastic_Config &c) #if !defined(ARCH_PORTDUINO) && !defined(ARCH_STM32WL) && !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR if (config.device.double_tap_as_button_press == false && c.payload_variant.device.double_tap_as_button_press == true && accelerometerThread->enabled == false) { + config.device.double_tap_as_button_press = c.payload_variant.device.double_tap_as_button_press; + accelerometerThread->enabled = true; accelerometerThread->start(); } #endif @@ -511,6 +513,8 @@ void AdminModule::handleSetConfig(const meshtastic_Config &c) #if !defined(ARCH_PORTDUINO) && !defined(ARCH_STM32WL) && !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR if (config.display.wake_on_tap_or_motion == false && c.payload_variant.display.wake_on_tap_or_motion == true && accelerometerThread->enabled == false) { + config.display.wake_on_tap_or_motion = c.payload_variant.display.wake_on_tap_or_motion; + accelerometerThread->enabled = true; accelerometerThread->start(); } #endif From 19f45d282f4305c3ef9781b717d549b4e176e58a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Sun, 29 Sep 2024 23:12:20 +0200 Subject: [PATCH 22/88] Update radiolib to 7.0.1 --- platformio.ini | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/platformio.ini b/platformio.ini index d781f0b12..b6b0d8249 100644 --- a/platformio.ini +++ b/platformio.ini @@ -89,9 +89,7 @@ monitor_speed = 115200 monitor_filters = direct lib_deps = - ;jgromes/RadioLib@~7.0.0 - ;7.0.1pre needed for LR1121 support and SX127x CRC Bugfix - https://github.com/jgromes/RadioLib.git#38fc7a97a4c195b7c10aa94215a1c53ec18a56ef + jgromes/RadioLib@~7.0.1 https://github.com/meshtastic/esp8266-oled-ssd1306.git#e16cee124fe26490cb14880c679321ad8ac89c95 ; ESP8266_SSD1306 https://github.com/mathertel/OneButton@~2.6.1 ; OneButton library for non-blocking button debounce https://github.com/meshtastic/arduino-fsm.git#7db3702bf0cfe97b783d6c72595e3f38e0b19159 From 3492c9aa995e83534a607b2e77a7f3f157e2d064 Mon Sep 17 00:00:00 2001 From: GUVWAF <78759985+GUVWAF@users.noreply.github.com> Date: Sun, 29 Sep 2024 23:17:23 +0200 Subject: [PATCH 23/88] Construct StoreForwardModule for Portduino as well (#4903) * Construct StoreForwardModule for Portduino as well * Remove duplicate variables --- src/modules/Modules.cpp | 8 +++++--- src/modules/StoreForwardModule.cpp | 3 --- 2 files changed, 5 insertions(+), 6 deletions(-) diff --git a/src/modules/Modules.cpp b/src/modules/Modules.cpp index eedb3a37d..554fad6a9 100644 --- a/src/modules/Modules.cpp +++ b/src/modules/Modules.cpp @@ -209,13 +209,15 @@ void setupModules() #if defined(USE_SX1280) && !MESHTASTIC_EXCLUDE_AUDIO audioModule = new AudioModule(); #endif -#if !MESHTASTIC_EXCLUDE_STOREFORWARD - storeForwardModule = new StoreForwardModule(); -#endif #if !MESHTASTIC_EXCLUDE_PAXCOUNTER paxcounterModule = new PaxcounterModule(); #endif #endif +#if defined(ARCH_ESP32) || defined(ARCH_PORTDUINO) +#if !MESHTASTIC_EXCLUDE_STOREFORWARD + storeForwardModule = new StoreForwardModule(); +#endif +#endif #if defined(ARCH_ESP32) || defined(ARCH_NRF52) || defined(ARCH_RP2040) #if !MESHTASTIC_EXCLUDE_EXTERNALNOTIFICATION externalNotificationModule = new ExternalNotificationModule(); diff --git a/src/modules/StoreForwardModule.cpp b/src/modules/StoreForwardModule.cpp index 29fbd8d92..5f30803a4 100644 --- a/src/modules/StoreForwardModule.cpp +++ b/src/modules/StoreForwardModule.cpp @@ -30,9 +30,6 @@ StoreForwardModule *storeForwardModule; -uint32_t lastHeartbeat = 0; -uint32_t heartbeatInterval = 60; // Default to 60 seconds, adjust as needed - int32_t StoreForwardModule::runOnce() { #if defined(ARCH_ESP32) || defined(ARCH_PORTDUINO) From 6f506cead573d4860448f686dedd0504699dd9af Mon Sep 17 00:00:00 2001 From: KodinLanewave Date: Sun, 29 Sep 2024 14:17:43 -0700 Subject: [PATCH 24/88] Update INA3221 to 1.0.1 (#4877) Added new release with compiler error fixes for INA3221 library - updating dependencies so new release will be included Co-authored-by: Ben Meadors --- platformio.ini | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/platformio.ini b/platformio.ini index d781f0b12..fb39b55a0 100644 --- a/platformio.ini +++ b/platformio.ini @@ -159,7 +159,7 @@ lib_deps = https://github.com/boschsensortec/Bosch-BSEC2-Library#v1.7.2502 boschsensortec/BME68x Sensor Library@^1.1.40407 - https://github.com/KodinLanewave/INA3221@^1.0.0 + https://github.com/KodinLanewave/INA3221@^1.0.1 lewisxhe/SensorLib@0.2.0 mprograms/QMC5883LCompass@^1.2.0 From b529099f906af25c40be06ff8573e2e4e4561eab Mon Sep 17 00:00:00 2001 From: Jason Murray <15822260+scruplelesswizard@users.noreply.github.com> Date: Sun, 29 Sep 2024 20:08:23 -0700 Subject: [PATCH 25/88] Update main_matrix.yml --- .github/workflows/main_matrix.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/main_matrix.yml b/.github/workflows/main_matrix.yml index b79b41d52..81c4615b4 100644 --- a/.github/workflows/main_matrix.yml +++ b/.github/workflows/main_matrix.yml @@ -235,7 +235,7 @@ jobs: path: ./*.elf retention-days: 30 - - uses: PicoCentauri/comment-artifact@main + - uses: scruplelesswizard/comment-artifact@main with: name: firmware-${{ steps.version.outputs.version }} description: "Download firmware-${{ steps.version.outputs.version }}.zip. This artifact will be available for 90 days from creation" From 8ad89ba72422fa4f4c84f8c4968e013d15858964 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Mon, 30 Sep 2024 05:14:22 -0500 Subject: [PATCH 26/88] Allow for better target level Radiolib exclude plumbing (#4906) * WIP * LR11x0 * Anothern * =1 --- platformio.ini | 40 ++++++++++++++++---------------- src/main.cpp | 13 +++++------ src/mesh/InterfacesTemplates.cpp | 6 +++++ src/mesh/LLCC68Interface.cpp | 4 +++- src/mesh/LLCC68Interface.h | 5 ++-- src/mesh/LR1110Interface.cpp | 5 +++- src/mesh/LR1110Interface.h | 5 ++-- src/mesh/LR1120Interface.cpp | 5 +++- src/mesh/LR1120Interface.h | 5 ++-- src/mesh/LR1121Interface.cpp | 4 +++- src/mesh/LR1121Interface.h | 4 +++- src/mesh/LR11x0Interface.cpp | 4 +++- src/mesh/LR11x0Interface.h | 3 ++- src/mesh/RF95Interface.cpp | 2 ++ src/mesh/RF95Interface.h | 3 ++- src/mesh/RadioLibRF95.cpp | 4 +++- src/mesh/RadioLibRF95.h | 2 ++ src/mesh/SX1262Interface.cpp | 4 +++- src/mesh/SX1262Interface.h | 4 +++- src/mesh/SX1268Interface.cpp | 4 +++- src/mesh/SX1268Interface.h | 2 ++ src/mesh/SX126xInterface.cpp | 4 +++- src/mesh/SX126xInterface.h | 2 ++ src/mesh/SX1280Interface.cpp | 2 ++ src/mesh/SX1280Interface.h | 3 ++- src/mesh/SX128xInterface.cpp | 4 +++- variants/rak4631/platformio.ini | 3 +++ 27 files changed, 98 insertions(+), 48 deletions(-) diff --git a/platformio.ini b/platformio.ini index 6f2a13865..4c85e2dd7 100644 --- a/platformio.ini +++ b/platformio.ini @@ -60,26 +60,26 @@ build_flags = -Wno-missing-field-initializers -DUSE_THREAD_NAMES -DTINYGPS_OPTION_NO_CUSTOM_FIELDS -DPB_ENABLE_MALLOC=1 - -DRADIOLIB_EXCLUDE_CC1101 - -DRADIOLIB_EXCLUDE_NRF24 - -DRADIOLIB_EXCLUDE_RF69 - -DRADIOLIB_EXCLUDE_SX1231 - -DRADIOLIB_EXCLUDE_SX1233 - -DRADIOLIB_EXCLUDE_SI443X - -DRADIOLIB_EXCLUDE_RFM2X - -DRADIOLIB_EXCLUDE_AFSK - -DRADIOLIB_EXCLUDE_BELL - -DRADIOLIB_EXCLUDE_HELLSCHREIBER - -DRADIOLIB_EXCLUDE_MORSE - -DRADIOLIB_EXCLUDE_RTTY - -DRADIOLIB_EXCLUDE_SSTV - -DRADIOLIB_EXCLUDE_AX25 - -DRADIOLIB_EXCLUDE_DIRECT_RECEIVE - -DRADIOLIB_EXCLUDE_BELL - -DRADIOLIB_EXCLUDE_PAGER - -DRADIOLIB_EXCLUDE_FSK4 - -DRADIOLIB_EXCLUDE_APRS - -DRADIOLIB_EXCLUDE_LORAWAN + -DRADIOLIB_EXCLUDE_CC1101=1 + -DRADIOLIB_EXCLUDE_NRF24=1 + -DRADIOLIB_EXCLUDE_RF69=1 + -DRADIOLIB_EXCLUDE_SX1231=1 + -DRADIOLIB_EXCLUDE_SX1233=1 + -DRADIOLIB_EXCLUDE_SI443X=1 + -DRADIOLIB_EXCLUDE_RFM2X=1 + -DRADIOLIB_EXCLUDE_AFSK=1 + -DRADIOLIB_EXCLUDE_BELL=1 + -DRADIOLIB_EXCLUDE_HELLSCHREIBER=1 + -DRADIOLIB_EXCLUDE_MORSE=1 + -DRADIOLIB_EXCLUDE_RTTY=1 + -DRADIOLIB_EXCLUDE_SSTV=1 + -DRADIOLIB_EXCLUDE_AX25=1 + -DRADIOLIB_EXCLUDE_DIRECT_RECEIVE=1 + -DRADIOLIB_EXCLUDE_BELL=1 + -DRADIOLIB_EXCLUDE_PAGER=1 + -DRADIOLIB_EXCLUDE_FSK4=1 + -DRADIOLIB_EXCLUDE_APRS=1 + -DRADIOLIB_EXCLUDE_LORAWAN=1 -DMESHTASTIC_EXCLUDE_DROPZONE=1 -DMESHTASTIC_EXCLUDE_REMOTEHARDWARE=1 -DBUILD_EPOCH=$UNIX_TIME diff --git a/src/main.cpp b/src/main.cpp index dfad9efbf..c11995837 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -885,7 +885,7 @@ void setup() } #endif -#if defined(RF95_IRQ) +#if defined(RF95_IRQ) && RADIOLIB_EXCLUDE_SX127X != 1 if ((!rIf) && (config.lora.region != meshtastic_Config_LoRaConfig_RegionCode_LORA_24)) { rIf = new RF95Interface(RadioLibHAL, LORA_CS, RF95_IRQ, RF95_RESET, RF95_DIO1); if (!rIf->init()) { @@ -899,7 +899,7 @@ void setup() } #endif -#if defined(USE_SX1262) && !defined(ARCH_PORTDUINO) && !defined(TCXO_OPTIONAL) +#if defined(USE_SX1262) && !defined(ARCH_PORTDUINO) && !defined(TCXO_OPTIONAL) && RADIOLIB_EXCLUDE_SX126X != 1 if ((!rIf) && (config.lora.region != meshtastic_Config_LoRaConfig_RegionCode_LORA_24)) { rIf = new SX1262Interface(RadioLibHAL, SX126X_CS, SX126X_DIO1, SX126X_RESET, SX126X_BUSY); if (!rIf->init()) { @@ -975,7 +975,7 @@ void setup() } #endif -#if defined(USE_LR1110) +#if defined(USE_LR1110) && RADIOLIB_EXCLUDE_LR11X0 != 1 if ((!rIf) && (config.lora.region != meshtastic_Config_LoRaConfig_RegionCode_LORA_24)) { rIf = new LR1110Interface(RadioLibHAL, LR1110_SPI_NSS_PIN, LR1110_IRQ_PIN, LR1110_NRESET_PIN, LR1110_BUSY_PIN); if (!rIf->init()) { @@ -989,7 +989,7 @@ void setup() } #endif -#if defined(USE_LR1120) +#if defined(USE_LR1120) && RADIOLIB_EXCLUDE_LR11X0 != 1 if (!rIf) { rIf = new LR1120Interface(RadioLibHAL, LR1120_SPI_NSS_PIN, LR1120_IRQ_PIN, LR1120_NRESET_PIN, LR1120_BUSY_PIN); if (!rIf->init()) { @@ -1003,7 +1003,7 @@ void setup() } #endif -#if defined(USE_LR1121) +#if defined(USE_LR1121) && RADIOLIB_EXCLUDE_LR11X0 != 1 if (!rIf) { rIf = new LR1121Interface(RadioLibHAL, LR1121_SPI_NSS_PIN, LR1121_IRQ_PIN, LR1121_NRESET_PIN, LR1121_BUSY_PIN); if (!rIf->init()) { @@ -1017,7 +1017,7 @@ void setup() } #endif -#if defined(USE_SX1280) +#if defined(USE_SX1280) && RADIOLIB_EXCLUDE_SX128X != 1 if (!rIf) { rIf = new SX1280Interface(RadioLibHAL, SX128X_CS, SX128X_DIO1, SX128X_RESET, SX128X_BUSY); if (!rIf->init()) { @@ -1032,7 +1032,6 @@ void setup() #endif // check if the radio chip matches the selected region - if ((config.lora.region == meshtastic_Config_LoRaConfig_RegionCode_LORA_24) && (!rIf->wideLora())) { LOG_WARN("Radio chip does not support 2.4GHz LoRa. Reverting to unset.\n"); config.lora.region = meshtastic_Config_LoRaConfig_RegionCode_UNSET; diff --git a/src/mesh/InterfacesTemplates.cpp b/src/mesh/InterfacesTemplates.cpp index 329f0b48e..2720e8525 100644 --- a/src/mesh/InterfacesTemplates.cpp +++ b/src/mesh/InterfacesTemplates.cpp @@ -8,13 +8,19 @@ #include "api/ServerAPI.h" // We need this declaration for proper linking in derived classes +#if RADIOLIB_EXCLUDE_SX126X != 1 template class SX126xInterface; template class SX126xInterface; template class SX126xInterface; +#endif +#if RADIOLIB_EXCLUDE_SX128X != 1 template class SX128xInterface; +#endif +#if RADIOLIB_EXCLUDE_LR11X0 != 1 template class LR11x0Interface; template class LR11x0Interface; template class LR11x0Interface; +#endif #ifdef ARCH_STM32WL template class SX126xInterface; #endif diff --git a/src/mesh/LLCC68Interface.cpp b/src/mesh/LLCC68Interface.cpp index 8109765a6..d92ea5450 100644 --- a/src/mesh/LLCC68Interface.cpp +++ b/src/mesh/LLCC68Interface.cpp @@ -1,3 +1,4 @@ +#if RADIOLIB_EXCLUDE_SX126X != 1 #include "LLCC68Interface.h" #include "configuration.h" #include "error.h" @@ -6,4 +7,5 @@ LLCC68Interface::LLCC68Interface(LockingArduinoHal *hal, RADIOLIB_PIN_TYPE cs, R RADIOLIB_PIN_TYPE busy) : SX126xInterface(hal, cs, irq, rst, busy) { -} \ No newline at end of file +} +#endif \ No newline at end of file diff --git a/src/mesh/LLCC68Interface.h b/src/mesh/LLCC68Interface.h index 7e0fa1439..1cd23e92b 100644 --- a/src/mesh/LLCC68Interface.h +++ b/src/mesh/LLCC68Interface.h @@ -1,5 +1,5 @@ #pragma once - +#if RADIOLIB_EXCLUDE_SX126X != 1 #include "SX126xInterface.h" /** @@ -15,4 +15,5 @@ class LLCC68Interface : public SX126xInterface public: LLCC68Interface(LockingArduinoHal *hal, RADIOLIB_PIN_TYPE cs, RADIOLIB_PIN_TYPE irq, RADIOLIB_PIN_TYPE rst, RADIOLIB_PIN_TYPE busy); -}; \ No newline at end of file +}; +#endif \ No newline at end of file diff --git a/src/mesh/LR1110Interface.cpp b/src/mesh/LR1110Interface.cpp index c000bd838..5dbd3ff38 100644 --- a/src/mesh/LR1110Interface.cpp +++ b/src/mesh/LR1110Interface.cpp @@ -1,3 +1,5 @@ +#if RADIOLIB_EXCLUDE_LR11X0 != 1 + #include "LR1110Interface.h" #include "configuration.h" #include "error.h" @@ -6,4 +8,5 @@ LR1110Interface::LR1110Interface(LockingArduinoHal *hal, RADIOLIB_PIN_TYPE cs, R RADIOLIB_PIN_TYPE busy) : LR11x0Interface(hal, cs, irq, rst, busy) { -} \ No newline at end of file +} +#endif \ No newline at end of file diff --git a/src/mesh/LR1110Interface.h b/src/mesh/LR1110Interface.h index 79e7c36ca..2a2e6e861 100644 --- a/src/mesh/LR1110Interface.h +++ b/src/mesh/LR1110Interface.h @@ -1,5 +1,5 @@ #pragma once - +#if RADIOLIB_EXCLUDE_LR11X0 != 1 #include "LR11x0Interface.h" /** @@ -10,4 +10,5 @@ class LR1110Interface : public LR11x0Interface public: LR1110Interface(LockingArduinoHal *hal, RADIOLIB_PIN_TYPE cs, RADIOLIB_PIN_TYPE irq, RADIOLIB_PIN_TYPE rst, RADIOLIB_PIN_TYPE busy); -}; \ No newline at end of file +}; +#endif \ No newline at end of file diff --git a/src/mesh/LR1120Interface.cpp b/src/mesh/LR1120Interface.cpp index 07e9e508d..a17ac87ef 100644 --- a/src/mesh/LR1120Interface.cpp +++ b/src/mesh/LR1120Interface.cpp @@ -1,3 +1,5 @@ +#if RADIOLIB_EXCLUDE_LR11X0 != 1 + #include "LR1120Interface.h" #include "configuration.h" #include "error.h" @@ -11,4 +13,5 @@ LR1120Interface::LR1120Interface(LockingArduinoHal *hal, RADIOLIB_PIN_TYPE cs, R bool LR1120Interface::wideLora() { return true; -} \ No newline at end of file +} +#endif \ No newline at end of file diff --git a/src/mesh/LR1120Interface.h b/src/mesh/LR1120Interface.h index a03fa0b20..d81a480a9 100644 --- a/src/mesh/LR1120Interface.h +++ b/src/mesh/LR1120Interface.h @@ -1,7 +1,7 @@ #pragma once +#if RADIOLIB_EXCLUDE_LR11X0 != 1 #include "LR11x0Interface.h" - /** * Our adapter for LR1120 wideband radios */ @@ -11,4 +11,5 @@ class LR1120Interface : public LR11x0Interface LR1120Interface(LockingArduinoHal *hal, RADIOLIB_PIN_TYPE cs, RADIOLIB_PIN_TYPE irq, RADIOLIB_PIN_TYPE rst, RADIOLIB_PIN_TYPE busy); bool wideLora() override; -}; \ No newline at end of file +}; +#endif \ No newline at end of file diff --git a/src/mesh/LR1121Interface.cpp b/src/mesh/LR1121Interface.cpp index 0d6bba6ea..29bd07d08 100644 --- a/src/mesh/LR1121Interface.cpp +++ b/src/mesh/LR1121Interface.cpp @@ -1,3 +1,4 @@ +#if RADIOLIB_EXCLUDE_LR11X0 != 1 #include "LR1121Interface.h" #include "configuration.h" #include "error.h" @@ -11,4 +12,5 @@ LR1121Interface::LR1121Interface(LockingArduinoHal *hal, RADIOLIB_PIN_TYPE cs, R bool LR1121Interface::wideLora() { return true; -} \ No newline at end of file +} +#endif \ No newline at end of file diff --git a/src/mesh/LR1121Interface.h b/src/mesh/LR1121Interface.h index 32a6f9492..ebc5b59a9 100644 --- a/src/mesh/LR1121Interface.h +++ b/src/mesh/LR1121Interface.h @@ -1,4 +1,5 @@ #pragma once +#if RADIOLIB_EXCLUDE_LR11X0 != 1 #include "LR11x0Interface.h" @@ -11,4 +12,5 @@ class LR1121Interface : public LR11x0Interface LR1121Interface(LockingArduinoHal *hal, RADIOLIB_PIN_TYPE cs, RADIOLIB_PIN_TYPE irq, RADIOLIB_PIN_TYPE rst, RADIOLIB_PIN_TYPE busy); bool wideLora() override; -}; \ No newline at end of file +}; +#endif \ No newline at end of file diff --git a/src/mesh/LR11x0Interface.cpp b/src/mesh/LR11x0Interface.cpp index f0f9119ea..6641634c4 100644 --- a/src/mesh/LR11x0Interface.cpp +++ b/src/mesh/LR11x0Interface.cpp @@ -1,3 +1,4 @@ +#if RADIOLIB_EXCLUDE_LR11X0 != 1 #include "LR11x0Interface.h" #include "Throttle.h" #include "configuration.h" @@ -284,4 +285,5 @@ template bool LR11x0Interface::sleep() #endif return true; -} \ No newline at end of file +} +#endif \ No newline at end of file diff --git a/src/mesh/LR11x0Interface.h b/src/mesh/LR11x0Interface.h index 5711b1f7f..4829ddc1d 100644 --- a/src/mesh/LR11x0Interface.h +++ b/src/mesh/LR11x0Interface.h @@ -1,5 +1,5 @@ #pragma once - +#if RADIOLIB_EXCLUDE_LR11X0 != 1 #include "RadioLibInterface.h" /** @@ -66,3 +66,4 @@ template class LR11x0Interface : public RadioLibInterface virtual void setStandby() override; }; +#endif \ No newline at end of file diff --git a/src/mesh/RF95Interface.cpp b/src/mesh/RF95Interface.cpp index 25df3258f..3cb6bfdda 100644 --- a/src/mesh/RF95Interface.cpp +++ b/src/mesh/RF95Interface.cpp @@ -1,3 +1,4 @@ +#if RADIOLIB_EXCLUDE_SX127X != 1 #include "RF95Interface.h" #include "MeshRadio.h" // kinda yucky, but we need to know which region we are in #include "RadioLibRF95.h" @@ -336,3 +337,4 @@ bool RF95Interface::sleep() return true; } +#endif \ No newline at end of file diff --git a/src/mesh/RF95Interface.h b/src/mesh/RF95Interface.h index a50cf93a2..327e57900 100644 --- a/src/mesh/RF95Interface.h +++ b/src/mesh/RF95Interface.h @@ -1,5 +1,5 @@ #pragma once - +#if RADIOLIB_EXCLUDE_SX127X != 1 #include "MeshRadio.h" // kinda yucky, but we need to know which region we are in #include "RadioLibInterface.h" #include "RadioLibRF95.h" @@ -69,3 +69,4 @@ class RF95Interface : public RadioLibInterface /** Some boards require GPIO control of tx vs rx paths */ void setTransmitEnable(bool txon); }; +#endif \ No newline at end of file diff --git a/src/mesh/RadioLibRF95.cpp b/src/mesh/RadioLibRF95.cpp index a202d4f4d..fe9bbdc93 100644 --- a/src/mesh/RadioLibRF95.cpp +++ b/src/mesh/RadioLibRF95.cpp @@ -1,3 +1,4 @@ +#if RADIOLIB_EXCLUDE_SX127X != 1 #include "RadioLibRF95.h" #include "configuration.h" @@ -81,4 +82,5 @@ uint8_t RadioLibRF95::readReg(uint8_t addr) { Module *mod = this->getMod(); return mod->SPIreadRegister(addr); -} \ No newline at end of file +} +#endif \ No newline at end of file diff --git a/src/mesh/RadioLibRF95.h b/src/mesh/RadioLibRF95.h index 3bdb794f2..916a33234 100644 --- a/src/mesh/RadioLibRF95.h +++ b/src/mesh/RadioLibRF95.h @@ -1,4 +1,5 @@ #pragma once +#if RADIOLIB_EXCLUDE_SX127X != 1 #include /*! @@ -69,3 +70,4 @@ class RadioLibRF95 : public SX1278 // use the previous value float currentLimit = 100; }; +#endif \ No newline at end of file diff --git a/src/mesh/SX1262Interface.cpp b/src/mesh/SX1262Interface.cpp index e96e72b71..4c0dea00b 100644 --- a/src/mesh/SX1262Interface.cpp +++ b/src/mesh/SX1262Interface.cpp @@ -1,3 +1,4 @@ +#if RADIOLIB_EXCLUDE_SX126X != 1 #include "SX1262Interface.h" #include "configuration.h" #include "error.h" @@ -6,4 +7,5 @@ SX1262Interface::SX1262Interface(LockingArduinoHal *hal, RADIOLIB_PIN_TYPE cs, R RADIOLIB_PIN_TYPE busy) : SX126xInterface(hal, cs, irq, rst, busy) { -} \ No newline at end of file +} +#endif \ No newline at end of file diff --git a/src/mesh/SX1262Interface.h b/src/mesh/SX1262Interface.h index 31a12ae90..6e4616c8b 100644 --- a/src/mesh/SX1262Interface.h +++ b/src/mesh/SX1262Interface.h @@ -1,3 +1,4 @@ +#if RADIOLIB_EXCLUDE_SX126X != 1 #pragma once #include "SX126xInterface.h" @@ -10,4 +11,5 @@ class SX1262Interface : public SX126xInterface public: SX1262Interface(LockingArduinoHal *hal, RADIOLIB_PIN_TYPE cs, RADIOLIB_PIN_TYPE irq, RADIOLIB_PIN_TYPE rst, RADIOLIB_PIN_TYPE busy); -}; \ No newline at end of file +}; +#endif \ No newline at end of file diff --git a/src/mesh/SX1268Interface.cpp b/src/mesh/SX1268Interface.cpp index ea299fce5..fe6e9af89 100644 --- a/src/mesh/SX1268Interface.cpp +++ b/src/mesh/SX1268Interface.cpp @@ -1,3 +1,4 @@ +#if RADIOLIB_EXCLUDE_SX126X != 1 #include "SX1268Interface.h" #include "configuration.h" #include "error.h" @@ -15,4 +16,5 @@ float SX1268Interface::getFreq() return 433.125f; else return savedFreq; -} \ No newline at end of file +} +#endif \ No newline at end of file diff --git a/src/mesh/SX1268Interface.h b/src/mesh/SX1268Interface.h index c8bcf20a7..cc6dd3534 100644 --- a/src/mesh/SX1268Interface.h +++ b/src/mesh/SX1268Interface.h @@ -1,4 +1,5 @@ #pragma once +#if RADIOLIB_EXCLUDE_SX126X != 1 #include "SX126xInterface.h" @@ -13,3 +14,4 @@ class SX1268Interface : public SX126xInterface SX1268Interface(LockingArduinoHal *hal, RADIOLIB_PIN_TYPE cs, RADIOLIB_PIN_TYPE irq, RADIOLIB_PIN_TYPE rst, RADIOLIB_PIN_TYPE busy); }; +#endif \ No newline at end of file diff --git a/src/mesh/SX126xInterface.cpp b/src/mesh/SX126xInterface.cpp index 30024daf0..a23c1e457 100644 --- a/src/mesh/SX126xInterface.cpp +++ b/src/mesh/SX126xInterface.cpp @@ -1,3 +1,4 @@ +#if RADIOLIB_EXCLUDE_SX126X != 1 #include "SX126xInterface.h" #include "configuration.h" #include "error.h" @@ -341,4 +342,5 @@ template bool SX126xInterface::sleep() #endif return true; -} \ No newline at end of file +} +#endif \ No newline at end of file diff --git a/src/mesh/SX126xInterface.h b/src/mesh/SX126xInterface.h index c437080c4..45b39a68a 100644 --- a/src/mesh/SX126xInterface.h +++ b/src/mesh/SX126xInterface.h @@ -1,4 +1,5 @@ #pragma once +#if RADIOLIB_EXCLUDE_SX126X != 1 #include "RadioLibInterface.h" @@ -68,3 +69,4 @@ template class SX126xInterface : public RadioLibInterface virtual void setStandby() override; }; +#endif \ No newline at end of file diff --git a/src/mesh/SX1280Interface.cpp b/src/mesh/SX1280Interface.cpp index 3287f141f..9e0d42122 100644 --- a/src/mesh/SX1280Interface.cpp +++ b/src/mesh/SX1280Interface.cpp @@ -1,3 +1,4 @@ +#if RADIOLIB_EXCLUDE_SX128X != 1 #include "SX1280Interface.h" #include "configuration.h" #include "error.h" @@ -7,3 +8,4 @@ SX1280Interface::SX1280Interface(LockingArduinoHal *hal, RADIOLIB_PIN_TYPE cs, R : SX128xInterface(hal, cs, irq, rst, busy) { } +#endif \ No newline at end of file diff --git a/src/mesh/SX1280Interface.h b/src/mesh/SX1280Interface.h index 8f2c4ec2e..534dd8084 100644 --- a/src/mesh/SX1280Interface.h +++ b/src/mesh/SX1280Interface.h @@ -1,5 +1,5 @@ #pragma once - +#if RADIOLIB_EXCLUDE_SX128X != 1 #include "SX128xInterface.h" /** @@ -12,3 +12,4 @@ class SX1280Interface : public SX128xInterface SX1280Interface(LockingArduinoHal *hal, RADIOLIB_PIN_TYPE cs, RADIOLIB_PIN_TYPE irq, RADIOLIB_PIN_TYPE rst, RADIOLIB_PIN_TYPE busy); }; +#endif diff --git a/src/mesh/SX128xInterface.cpp b/src/mesh/SX128xInterface.cpp index 5c740099c..2a1bb4e41 100644 --- a/src/mesh/SX128xInterface.cpp +++ b/src/mesh/SX128xInterface.cpp @@ -1,3 +1,4 @@ +#if RADIOLIB_EXCLUDE_SX128X != 1 #include "SX128xInterface.h" #include "Throttle.h" #include "configuration.h" @@ -313,4 +314,5 @@ template bool SX128xInterface::sleep() #endif return true; -} \ No newline at end of file +} +#endif \ No newline at end of file diff --git a/variants/rak4631/platformio.ini b/variants/rak4631/platformio.ini index 8f1006eca..77b5e975c 100644 --- a/variants/rak4631/platformio.ini +++ b/variants/rak4631/platformio.ini @@ -9,6 +9,9 @@ build_flags = ${nrf52840_base.build_flags} -Ivariants/rak4631 -D RAK_4631 -DEINK_DISPLAY_MODEL=GxEPD2_213_BN -DEINK_WIDTH=250 -DEINK_HEIGHT=122 + -DRADIOLIB_EXCLUDE_SX128X=1 + -DRADIOLIB_EXCLUDE_SX127X=1 + -DRADIOLIB_EXCLUDE_LR11X0=1 build_src_filter = ${nrf52_base.build_src_filter} +<../variants/rak4631> + + + lib_deps = ${nrf52840_base.lib_deps} From a5bcf482402fca4f1d83ebcf3fa45ee570081ebb Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Mon, 30 Sep 2024 18:12:35 +0200 Subject: [PATCH 27/88] Welp it's 7.0.2 now but the branch is still open :-) --- platformio.ini | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/platformio.ini b/platformio.ini index b6b0d8249..ca05342c9 100644 --- a/platformio.ini +++ b/platformio.ini @@ -89,7 +89,8 @@ monitor_speed = 115200 monitor_filters = direct lib_deps = - jgromes/RadioLib@~7.0.1 + ;jgromes/RadioLib@~7.0.2 + https://github.com/jgromes/RadioLib.git#5a9ff5a4912f87918390348c8caa54ea8a6afada ; Radiolib 7.0.2pre https://github.com/meshtastic/esp8266-oled-ssd1306.git#e16cee124fe26490cb14880c679321ad8ac89c95 ; ESP8266_SSD1306 https://github.com/mathertel/OneButton@~2.6.1 ; OneButton library for non-blocking button debounce https://github.com/meshtastic/arduino-fsm.git#7db3702bf0cfe97b783d6c72595e3f38e0b19159 From 5fcad1d8c5b4340c196d0559a5aee2d977d8c6ee Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Mon, 30 Sep 2024 18:12:35 +0200 Subject: [PATCH 28/88] Welp it's 7.0.2 now but the branch is still open :-) --- platformio.ini | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/platformio.ini b/platformio.ini index 4c85e2dd7..009635686 100644 --- a/platformio.ini +++ b/platformio.ini @@ -89,7 +89,8 @@ monitor_speed = 115200 monitor_filters = direct lib_deps = - jgromes/RadioLib@~7.0.1 + ;jgromes/RadioLib@~7.0.2 + https://github.com/jgromes/RadioLib.git#5a9ff5a4912f87918390348c8caa54ea8a6afada ; Radiolib 7.0.2pre https://github.com/meshtastic/esp8266-oled-ssd1306.git#e16cee124fe26490cb14880c679321ad8ac89c95 ; ESP8266_SSD1306 https://github.com/mathertel/OneButton@~2.6.1 ; OneButton library for non-blocking button debounce https://github.com/meshtastic/arduino-fsm.git#7db3702bf0cfe97b783d6c72595e3f38e0b19159 From 199566a996c4817e85778dc26f81264ee7dba487 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Mon, 30 Sep 2024 21:11:48 +0200 Subject: [PATCH 29/88] let's see if this works --- .github/workflows/main_matrix.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/main_matrix.yml b/.github/workflows/main_matrix.yml index 81c4615b4..42fee7a16 100644 --- a/.github/workflows/main_matrix.yml +++ b/.github/workflows/main_matrix.yml @@ -35,7 +35,7 @@ jobs: name: Checkout base - id: jsonStep run: | - if [[ "${{ github.head_ref }}" == "master" ]]; then + if [[ "${{ github.head_ref }}" == "" ]]; then TARGETS=$(./bin/generate_ci_matrix.py ${{matrix.arch}}) else TARGETS=$(./bin/generate_ci_matrix.py ${{matrix.arch}} quick) From 810a79668ca27b74e2f5c4f3bb493b20b544986c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Mon, 30 Sep 2024 21:54:00 +0200 Subject: [PATCH 30/88] 7.0.2 dropped --- platformio.ini | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/platformio.ini b/platformio.ini index 009635686..4c35dbd5c 100644 --- a/platformio.ini +++ b/platformio.ini @@ -89,8 +89,7 @@ monitor_speed = 115200 monitor_filters = direct lib_deps = - ;jgromes/RadioLib@~7.0.2 - https://github.com/jgromes/RadioLib.git#5a9ff5a4912f87918390348c8caa54ea8a6afada ; Radiolib 7.0.2pre + jgromes/RadioLib@~7.0.2 https://github.com/meshtastic/esp8266-oled-ssd1306.git#e16cee124fe26490cb14880c679321ad8ac89c95 ; ESP8266_SSD1306 https://github.com/mathertel/OneButton@~2.6.1 ; OneButton library for non-blocking button debounce https://github.com/meshtastic/arduino-fsm.git#7db3702bf0cfe97b783d6c72595e3f38e0b19159 From dd587419c7ae0f351b513822af128eb1d596c5ee Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Mon, 30 Sep 2024 17:06:31 -0500 Subject: [PATCH 31/88] Regenerate public key on boot, to avoid accidental mismatch. (#4916) * Regenerate public key on boot, to avoid accidental mismatch. * Fix ifdefs --- src/mesh/NodeDB.cpp | 46 +++++++++++++++++++-------------------------- 1 file changed, 19 insertions(+), 27 deletions(-) diff --git a/src/mesh/NodeDB.cpp b/src/mesh/NodeDB.cpp index 7760ae0e1..36b9f3ff4 100644 --- a/src/mesh/NodeDB.cpp +++ b/src/mesh/NodeDB.cpp @@ -132,39 +132,31 @@ NodeDB::NodeDB() config.security.serial_enabled = config.device.serial_enabled; config.security.is_managed = config.device.is_managed; } -#if !(MESHTASTIC_EXCLUDE_PKI) + +#if !(MESHTASTIC_EXCLUDE_PKI_KEYGEN || MESHTASTIC_EXCLUDE_PKI) + bool keygenSuccess = false; + if (config.security.private_key.size == 32) { + if (crypto->regeneratePublicKey(config.security.public_key.bytes, config.security.private_key.bytes)) { + keygenSuccess = true; + } + } else { + LOG_INFO("Generating new PKI keys\n"); + crypto->generateKeyPair(config.security.public_key.bytes, config.security.private_key.bytes); + keygenSuccess = true; + } + if (keygenSuccess) { + config.security.public_key.size = 32; + config.security.private_key.size = 32; + owner.public_key.size = 32; + memcpy(owner.public_key.bytes, config.security.public_key.bytes, 32); + } +#elif !(MESHTASTIC_EXCLUDE_PKI) // Calculate Curve25519 public and private keys - printBytes("Old Pubkey", config.security.public_key.bytes, 32); if (config.security.private_key.size == 32 && config.security.public_key.size == 32) { - LOG_INFO("Using saved PKI keys\n"); owner.public_key.size = config.security.public_key.size; memcpy(owner.public_key.bytes, config.security.public_key.bytes, config.security.public_key.size); crypto->setDHPrivateKey(config.security.private_key.bytes); - } else { -#if !(MESHTASTIC_EXCLUDE_PKI_KEYGEN) - bool keygenSuccess = false; - if (config.security.private_key.size == 32) { - LOG_INFO("Calculating PKI Public Key\n"); - if (crypto->regeneratePublicKey(config.security.public_key.bytes, config.security.private_key.bytes)) { - keygenSuccess = true; - } - } else { - LOG_INFO("Generating new PKI keys\n"); - crypto->generateKeyPair(config.security.public_key.bytes, config.security.private_key.bytes); - keygenSuccess = true; - } - if (keygenSuccess) { - config.security.public_key.size = 32; - config.security.private_key.size = 32; - printBytes("New Pubkey", config.security.public_key.bytes, 32); - owner.public_key.size = 32; - memcpy(owner.public_key.bytes, config.security.public_key.bytes, 32); - } -#else - LOG_INFO("No PKI keys set, and generation disabled!\n"); -#endif } - #endif info->user = TypeConversions::ConvertToUserLite(owner); From 1dace9a50892d114bc97e03958d016b18c92f7cc Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Mon, 30 Sep 2024 17:35:35 -0500 Subject: [PATCH 32/88] [create-pull-request] automated change (#4917) Co-authored-by: thebentern <9000580+thebentern@users.noreply.github.com> --- protobufs | 2 +- src/mesh/generated/meshtastic/atak.pb.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/protobufs b/protobufs index 83c78e26e..61d7ca656 160000 --- a/protobufs +++ b/protobufs @@ -1 +1 @@ -Subproject commit 83c78e26e39031ae1c17ba5e50d0898842719c7f +Subproject commit 61d7ca65652dfe832ead74719700d3d33d6bae7c diff --git a/src/mesh/generated/meshtastic/atak.pb.h b/src/mesh/generated/meshtastic/atak.pb.h index 50b57cd04..7d1ef2995 100644 --- a/src/mesh/generated/meshtastic/atak.pb.h +++ b/src/mesh/generated/meshtastic/atak.pb.h @@ -141,7 +141,7 @@ typedef struct _meshtastic_TAKPacket { /* ATAK GeoChat message */ meshtastic_GeoChat chat; /* Generic CoT detail XML - May be compressed / truncated by the sender */ + May be compressed / truncated by the sender (EUD) */ meshtastic_TAKPacket_detail_t detail; } payload_variant; } meshtastic_TAKPacket; From 553514e3b78b30c73849121694cdf2c52192b2c0 Mon Sep 17 00:00:00 2001 From: TheMalkavien Date: Tue, 1 Oct 2024 00:56:29 +0200 Subject: [PATCH 33/88] Fix #4911 : Partially rework some code to remove warnings about potential non-aligned memory accesses (#4912) * * Adding the -Wcast-align compilation flag for the rp2040. * * Some rework to use a struct to access radio data * Buffer will not be accessed by arithmetic pointer anymore * * Remplace arithmetic pointer to avoid Warning * * Avoid 2 little artitmetic pointer --------- Co-authored-by: Ben Meadors --- arch/rp2xx0/rp2040.ini | 2 +- src/gps/GPS.cpp | 4 ++-- src/gps/NMEAWPL.cpp | 7 +++++-- src/mesh/CryptoEngine.cpp | 11 +++++------ src/mesh/RadioInterface.cpp | 24 +++++++++++------------- src/mesh/RadioInterface.h | 17 +++++++++++++++-- src/mesh/RadioLibInterface.cpp | 26 ++++++++++++-------------- 7 files changed, 51 insertions(+), 40 deletions(-) diff --git a/arch/rp2xx0/rp2040.ini b/arch/rp2xx0/rp2040.ini index d3f27a676..5b4ec74d2 100644 --- a/arch/rp2xx0/rp2040.ini +++ b/arch/rp2xx0/rp2040.ini @@ -7,7 +7,7 @@ platform_packages = framework-arduinopico@https://github.com/earlephilhower/ardu board_build.core = earlephilhower board_build.filesystem_size = 0.5m build_flags = - ${arduino_base.build_flags} -Wno-unused-variable + ${arduino_base.build_flags} -Wno-unused-variable -Wcast-align -Isrc/platform/rp2xx0 -D__PLAT_RP2040__ # -D _POSIX_THREADS diff --git a/src/gps/GPS.cpp b/src/gps/GPS.cpp index b6d2776bc..f2b15ba78 100644 --- a/src/gps/GPS.cpp +++ b/src/gps/GPS.cpp @@ -91,9 +91,9 @@ 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 const *payload = (uint32_t *)(message + 6); for (size_t i = 0; i < (length - 10) / 4; i++) { - uint32_t pl = payload[i]; + uint32_t pl = 0; + memcpy(&pl, (message + 6) + (i * sizeof(uint32_t)), sizeof(uint32_t)); // avoid pointer dereference cksum += pl; } diff --git a/src/gps/NMEAWPL.cpp b/src/gps/NMEAWPL.cpp index 71943b76c..f528c4607 100644 --- a/src/gps/NMEAWPL.cpp +++ b/src/gps/NMEAWPL.cpp @@ -75,10 +75,13 @@ uint32_t printWPL(char *buf, size_t bufsz, const meshtastic_Position &pos, const uint32_t printGGA(char *buf, size_t bufsz, const meshtastic_Position &pos) { GeoCoord geoCoord(pos.latitude_i, pos.longitude_i, pos.altitude); - tm *t = gmtime((time_t *)&pos.timestamp); + time_t timestamp = pos.timestamp; + + tm *t = gmtime(×tamp); if (getRTCQuality() > 0) { // use the device clock if we got time from somewhere. If not, use the GPS timestamp. uint32_t rtc_sec = getValidTime(RTCQuality::RTCQualityDevice); - t = gmtime((time_t *)&rtc_sec); + timestamp = rtc_sec; + t = gmtime(×tamp); } uint32_t len = snprintf( diff --git a/src/mesh/CryptoEngine.cpp b/src/mesh/CryptoEngine.cpp index 535e11e9b..fd3dd7a54 100644 --- a/src/mesh/CryptoEngine.cpp +++ b/src/mesh/CryptoEngine.cpp @@ -69,9 +69,8 @@ bool CryptoEngine::encryptCurve25519(uint32_t toNode, uint32_t fromNode, uint64_ uint32_t *extraNonce; long extraNonceTmp = random(); auth = bytesOut + numBytes; - extraNonce = (uint32_t *)(auth + 8); - memcpy(extraNonce, &extraNonceTmp, - 4); // do not use dereference on potential non aligned pointers : *extraNonce = extraNonceTmp; + memcpy((uint8_t *)(auth + 8), &extraNonceTmp, + sizeof(uint32_t)); // do not use dereference on potential non aligned pointers : *extraNonce = extraNonceTmp; LOG_INFO("Random nonce value: %d\n", extraNonceTmp); meshtastic_NodeInfoLite *node = nodeDB->getMeshNode(toNode); if (node->num < 1 || node->user.public_key.size == 0) { @@ -88,8 +87,8 @@ bool CryptoEngine::encryptCurve25519(uint32_t toNode, uint32_t fromNode, uint64_ printBytes("Attempting encrypt using shared_key starting with: ", shared_key, 8); aes_ccm_ae(shared_key, 32, nonce, 8, bytes, numBytes, nullptr, 0, bytesOut, auth); // this can write up to 15 bytes longer than numbytes past bytesOut - memcpy(extraNonce, &extraNonceTmp, - 4); // do not use dereference on potential non aligned pointers : *extraNonce = extraNonceTmp; + memcpy((uint8_t *)(auth + 8), &extraNonceTmp, + sizeof(uint32_t)); // do not use dereference on potential non aligned pointers : *extraNonce = extraNonceTmp; return true; } @@ -105,7 +104,7 @@ bool CryptoEngine::decryptCurve25519(uint32_t fromNode, uint64_t packetNum, size uint32_t extraNonce; // pointer was not really used auth = bytes + numBytes - 12; #ifndef PIO_UNIT_TESTING - memcpy(&extraNonce, auth + 8, 4); // do not use dereference on potential non aligned pointers : (uint32_t *)(auth + 8); + memcpy(&extraNonce, auth + 8, sizeof(uint32_t)); // do not use dereference on potential non aligned pointers : (uint32_t *)(auth + 8); LOG_INFO("Random nonce value: %d\n", extraNonce); meshtastic_NodeInfoLite *node = nodeDB->getMeshNode(fromNode); diff --git a/src/mesh/RadioInterface.cpp b/src/mesh/RadioInterface.cpp index 6fca67188..fe24624ce 100644 --- a/src/mesh/RadioInterface.cpp +++ b/src/mesh/RadioInterface.cpp @@ -595,26 +595,24 @@ size_t RadioInterface::beginSending(meshtastic_MeshPacket *p) lastTxStart = millis(); - PacketHeader *h = (PacketHeader *)radiobuf; - - h->from = p->from; - h->to = p->to; - h->id = p->id; - h->channel = p->channel; - h->next_hop = 0; // *** For future use *** - h->relay_node = 0; // *** For future use *** + radioBuffer.header.from = p->from; + radioBuffer.header.to = p->to; + radioBuffer.header.id = p->id; + radioBuffer.header.channel = p->channel; + radioBuffer.header.next_hop = 0; // *** For future use *** + radioBuffer.header.relay_node = 0; // *** For future use *** if (p->hop_limit > HOP_MAX) { LOG_WARN("hop limit %d is too high, setting to %d\n", p->hop_limit, HOP_RELIABLE); p->hop_limit = HOP_RELIABLE; } - h->flags = p->hop_limit | (p->want_ack ? PACKET_FLAGS_WANT_ACK_MASK : 0) | (p->via_mqtt ? PACKET_FLAGS_VIA_MQTT_MASK : 0); - h->flags |= (p->hop_start << PACKET_FLAGS_HOP_START_SHIFT) & PACKET_FLAGS_HOP_START_MASK; + radioBuffer.header.flags = p->hop_limit | (p->want_ack ? PACKET_FLAGS_WANT_ACK_MASK : 0) | (p->via_mqtt ? PACKET_FLAGS_VIA_MQTT_MASK : 0); + radioBuffer.header.flags |= (p->hop_start << PACKET_FLAGS_HOP_START_SHIFT) & PACKET_FLAGS_HOP_START_MASK; // if the sender nodenum is zero, that means uninitialized - assert(h->from); + assert(radioBuffer.header.from); - memcpy(radiobuf + sizeof(PacketHeader), p->encrypted.bytes, p->encrypted.size); + memcpy(radioBuffer.payload, p->encrypted.bytes, p->encrypted.size); sendingPacket = p; return p->encrypted.size + sizeof(PacketHeader); -} +} \ No newline at end of file diff --git a/src/mesh/RadioInterface.h b/src/mesh/RadioInterface.h index 129861441..6df51ce1a 100644 --- a/src/mesh/RadioInterface.h +++ b/src/mesh/RadioInterface.h @@ -45,6 +45,20 @@ typedef struct { uint8_t relay_node; } PacketHeader; +/** + * This structure represent the structured buffer : a PacketHeader then the payload. The whole is + * MAX_LORA_PAYLOAD_LEN + 1 length + * It makes the use of its data easier, and avoids manipulating pointers (and potential non aligned accesses) + */ +typedef struct { + /** The header, as defined just before */ + PacketHeader header; + + /** The payload, of maximum length minus the header, aligned just to be sure */ + uint8_t payload[MAX_LORA_PAYLOAD_LEN + 1 - sizeof(PacketHeader)] __attribute__ ((__aligned__)); + +} RadioBuffer; + /** * Basic operations all radio chipsets must implement. * @@ -91,8 +105,7 @@ class RadioInterface /** * A temporary buffer used for sending/receiving packets, sized to hold the biggest buffer we might need * */ - uint8_t radiobuf[MAX_LORA_PAYLOAD_LEN + 1]; - + RadioBuffer radioBuffer __attribute__ ((__aligned__)); /** * Enqueue a received packet for the registered receiver */ diff --git a/src/mesh/RadioLibInterface.cpp b/src/mesh/RadioLibInterface.cpp index aee43676d..647add0e5 100644 --- a/src/mesh/RadioLibInterface.cpp +++ b/src/mesh/RadioLibInterface.cpp @@ -387,7 +387,7 @@ void RadioLibInterface::handleReceiveInterrupt() } #endif - int state = iface->readData(radiobuf, length); + int state = iface->readData((uint8_t*)&radioBuffer, length); if (state != RADIOLIB_ERR_NONE) { LOG_ERROR("ignoring received packet due to error=%d\n", state); rxBad++; @@ -397,7 +397,6 @@ void RadioLibInterface::handleReceiveInterrupt() } else { // Skip the 4 headers that are at the beginning of the rxBuf int32_t payloadLen = length - sizeof(PacketHeader); - const uint8_t *payload = radiobuf + sizeof(PacketHeader); // check for short packets if (payloadLen < 0) { @@ -405,10 +404,9 @@ void RadioLibInterface::handleReceiveInterrupt() rxBad++; airTime->logAirtime(RX_ALL_LOG, xmitMsec); } else { - const PacketHeader *h = (PacketHeader *)radiobuf; rxGood++; // altered packet with "from == 0" can do Remote Node Administration without permission - if (h->from == 0) { + if (radioBuffer.header.from == 0) { LOG_WARN("ignoring received packet without sender\n"); return; } @@ -418,22 +416,22 @@ void RadioLibInterface::handleReceiveInterrupt() // nodes. meshtastic_MeshPacket *mp = packetPool.allocZeroed(); - mp->from = h->from; - mp->to = h->to; - mp->id = h->id; - mp->channel = h->channel; + mp->from = radioBuffer.header.from; + mp->to = radioBuffer.header.to; + mp->id = radioBuffer.header.id; + mp->channel = radioBuffer.header.channel; assert(HOP_MAX <= PACKET_FLAGS_HOP_LIMIT_MASK); // If hopmax changes, carefully check this code - mp->hop_limit = h->flags & PACKET_FLAGS_HOP_LIMIT_MASK; - mp->hop_start = (h->flags & PACKET_FLAGS_HOP_START_MASK) >> PACKET_FLAGS_HOP_START_SHIFT; - mp->want_ack = !!(h->flags & PACKET_FLAGS_WANT_ACK_MASK); - mp->via_mqtt = !!(h->flags & PACKET_FLAGS_VIA_MQTT_MASK); + mp->hop_limit = radioBuffer.header.flags & PACKET_FLAGS_HOP_LIMIT_MASK; + mp->hop_start = (radioBuffer.header.flags & PACKET_FLAGS_HOP_START_MASK) >> PACKET_FLAGS_HOP_START_SHIFT; + mp->want_ack = !!(radioBuffer.header.flags & PACKET_FLAGS_WANT_ACK_MASK); + mp->via_mqtt = !!(radioBuffer.header.flags & PACKET_FLAGS_VIA_MQTT_MASK); addReceiveMetadata(mp); mp->which_payload_variant = meshtastic_MeshPacket_encrypted_tag; // Mark that the payload is still encrypted at this point assert(((uint32_t)payloadLen) <= sizeof(mp->encrypted.bytes)); - memcpy(mp->encrypted.bytes, payload, payloadLen); + memcpy(mp->encrypted.bytes, radioBuffer.payload, payloadLen); mp->encrypted.size = payloadLen; printPacket("Lora RX", mp); @@ -475,7 +473,7 @@ void RadioLibInterface::startSend(meshtastic_MeshPacket *txp) size_t numbytes = beginSending(txp); - int res = iface->startTransmit(radiobuf, numbytes); + int res = iface->startTransmit((uint8_t*)&radioBuffer, numbytes); if (res != RADIOLIB_ERR_NONE) { LOG_ERROR("startTransmit failed, error=%d\n", res); RECORD_CRITICALERROR(meshtastic_CriticalErrorCode_RADIO_SPI_BUG); From dc55d7dd987b04658abb9a58f1c65f60cf885818 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Mon, 30 Sep 2024 18:07:11 -0500 Subject: [PATCH 34/88] Trunk it --- src/mesh/CryptoEngine.cpp | 3 ++- src/mesh/RadioInterface.cpp | 3 ++- src/mesh/RadioLibInterface.cpp | 4 ++-- src/mesh/Router.cpp | 4 ++-- 4 files changed, 8 insertions(+), 6 deletions(-) diff --git a/src/mesh/CryptoEngine.cpp b/src/mesh/CryptoEngine.cpp index fd3dd7a54..085055f41 100644 --- a/src/mesh/CryptoEngine.cpp +++ b/src/mesh/CryptoEngine.cpp @@ -104,7 +104,8 @@ bool CryptoEngine::decryptCurve25519(uint32_t fromNode, uint64_t packetNum, size uint32_t extraNonce; // pointer was not really used auth = bytes + numBytes - 12; #ifndef PIO_UNIT_TESTING - memcpy(&extraNonce, auth + 8, sizeof(uint32_t)); // do not use dereference on potential non aligned pointers : (uint32_t *)(auth + 8); + memcpy(&extraNonce, auth + 8, + sizeof(uint32_t)); // do not use dereference on potential non aligned pointers : (uint32_t *)(auth + 8); LOG_INFO("Random nonce value: %d\n", extraNonce); meshtastic_NodeInfoLite *node = nodeDB->getMeshNode(fromNode); diff --git a/src/mesh/RadioInterface.cpp b/src/mesh/RadioInterface.cpp index fe24624ce..683ae7e01 100644 --- a/src/mesh/RadioInterface.cpp +++ b/src/mesh/RadioInterface.cpp @@ -605,7 +605,8 @@ size_t RadioInterface::beginSending(meshtastic_MeshPacket *p) LOG_WARN("hop limit %d is too high, setting to %d\n", p->hop_limit, HOP_RELIABLE); p->hop_limit = HOP_RELIABLE; } - radioBuffer.header.flags = p->hop_limit | (p->want_ack ? PACKET_FLAGS_WANT_ACK_MASK : 0) | (p->via_mqtt ? PACKET_FLAGS_VIA_MQTT_MASK : 0); + radioBuffer.header.flags = + p->hop_limit | (p->want_ack ? PACKET_FLAGS_WANT_ACK_MASK : 0) | (p->via_mqtt ? PACKET_FLAGS_VIA_MQTT_MASK : 0); radioBuffer.header.flags |= (p->hop_start << PACKET_FLAGS_HOP_START_SHIFT) & PACKET_FLAGS_HOP_START_MASK; // if the sender nodenum is zero, that means uninitialized diff --git a/src/mesh/RadioLibInterface.cpp b/src/mesh/RadioLibInterface.cpp index 647add0e5..664709ed1 100644 --- a/src/mesh/RadioLibInterface.cpp +++ b/src/mesh/RadioLibInterface.cpp @@ -387,7 +387,7 @@ void RadioLibInterface::handleReceiveInterrupt() } #endif - int state = iface->readData((uint8_t*)&radioBuffer, length); + int state = iface->readData((uint8_t *)&radioBuffer, length); if (state != RADIOLIB_ERR_NONE) { LOG_ERROR("ignoring received packet due to error=%d\n", state); rxBad++; @@ -473,7 +473,7 @@ void RadioLibInterface::startSend(meshtastic_MeshPacket *txp) size_t numbytes = beginSending(txp); - int res = iface->startTransmit((uint8_t*)&radioBuffer, numbytes); + int res = iface->startTransmit((uint8_t *)&radioBuffer, numbytes); if (res != RADIOLIB_ERR_NONE) { LOG_ERROR("startTransmit failed, error=%d\n", res); RECORD_CRITICALERROR(meshtastic_CriticalErrorCode_RADIO_SPI_BUG); diff --git a/src/mesh/Router.cpp b/src/mesh/Router.cpp index f06f54165..bb04b66ac 100644 --- a/src/mesh/Router.cpp +++ b/src/mesh/Router.cpp @@ -36,8 +36,8 @@ static MemoryDynamic staticPool; Allocator &packetPool = staticPool; -static uint8_t bytes[MAX_LORA_PAYLOAD_LEN + 1] __attribute__ ((__aligned__)); -static uint8_t ScratchEncrypted[MAX_LORA_PAYLOAD_LEN + 1] __attribute__ ((__aligned__)); +static uint8_t bytes[MAX_LORA_PAYLOAD_LEN + 1] __attribute__((__aligned__)); +static uint8_t ScratchEncrypted[MAX_LORA_PAYLOAD_LEN + 1] __attribute__((__aligned__)); /** * Constructor From 8d288d5a3c6955ba06807a4b6cb7b9b1b60a930d Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Mon, 30 Sep 2024 19:26:35 -0500 Subject: [PATCH 35/88] Only on pull request --- .github/workflows/main_matrix.yml | 1 + 1 file changed, 1 insertion(+) diff --git a/.github/workflows/main_matrix.yml b/.github/workflows/main_matrix.yml index 42fee7a16..277003a61 100644 --- a/.github/workflows/main_matrix.yml +++ b/.github/workflows/main_matrix.yml @@ -236,6 +236,7 @@ jobs: retention-days: 30 - uses: scruplelesswizard/comment-artifact@main + if: ${{ github.event_name == 'pull_request' }} with: name: firmware-${{ steps.version.outputs.version }} description: "Download firmware-${{ steps.version.outputs.version }}.zip. This artifact will be available for 90 days from creation" From b769d9f8542d109f37922c9fad3d027265b0009d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Tue, 1 Oct 2024 13:14:51 +0200 Subject: [PATCH 36/88] change workflow to build one zip per processor arch --- .github/actions/build-variant/action.yml | 6 +- .github/workflows/build_esp32.yml | 1 + .github/workflows/build_esp32_c3.yml | 1 + .github/workflows/build_esp32_c6.yml | 1 + .github/workflows/build_esp32_s3.yml | 1 + .github/workflows/build_nrf52.yml | 1 + .github/workflows/build_rpi2040.yml | 1 + .github/workflows/build_stm32.yml | 2 + .github/workflows/main_matrix.yml | 174 ++++++++++++----------- 9 files changed, 102 insertions(+), 86 deletions(-) diff --git a/.github/actions/build-variant/action.yml b/.github/actions/build-variant/action.yml index f9410eb03..80d2a56bb 100644 --- a/.github/actions/build-variant/action.yml +++ b/.github/actions/build-variant/action.yml @@ -31,6 +31,10 @@ inputs: description: Include the web UI in the build required: false default: "false" + arch: + description: Processor arch name + required: true + default: "esp32" runs: using: composite @@ -84,7 +88,7 @@ runs: - name: Store binaries as an artifact uses: actions/upload-artifact@v4 with: - name: firmware-${{ inputs.board }}-${{ steps.version.outputs.version }}.zip + name: firmware-${{ inputs.arch }}-${{ inputs.board }}-${{ steps.version.outputs.version }}.zip overwrite: true path: | ${{ inputs.artifact-paths }} diff --git a/.github/workflows/build_esp32.yml b/.github/workflows/build_esp32.yml index 041191d34..7d069e3db 100644 --- a/.github/workflows/build_esp32.yml +++ b/.github/workflows/build_esp32.yml @@ -31,3 +31,4 @@ jobs: release/*.bin release/*.elf include-web-ui: true + arch: esp32 diff --git a/.github/workflows/build_esp32_c3.yml b/.github/workflows/build_esp32_c3.yml index ddc2e2859..5234dbe81 100644 --- a/.github/workflows/build_esp32_c3.yml +++ b/.github/workflows/build_esp32_c3.yml @@ -32,3 +32,4 @@ jobs: artifact-paths: | release/*.bin release/*.elf + arch: esp32c3 diff --git a/.github/workflows/build_esp32_c6.yml b/.github/workflows/build_esp32_c6.yml index 3be813afa..66f2764a6 100644 --- a/.github/workflows/build_esp32_c6.yml +++ b/.github/workflows/build_esp32_c6.yml @@ -33,3 +33,4 @@ jobs: artifact-paths: | release/*.bin release/*.elf + arch: esp32c6 diff --git a/.github/workflows/build_esp32_s3.yml b/.github/workflows/build_esp32_s3.yml index 29857ef17..554b37cef 100644 --- a/.github/workflows/build_esp32_s3.yml +++ b/.github/workflows/build_esp32_s3.yml @@ -31,3 +31,4 @@ jobs: release/*.bin release/*.elf include-web-ui: true + arch: esp32s3 diff --git a/.github/workflows/build_nrf52.yml b/.github/workflows/build_nrf52.yml index 606cb8a3e..ce26838f2 100644 --- a/.github/workflows/build_nrf52.yml +++ b/.github/workflows/build_nrf52.yml @@ -25,3 +25,4 @@ jobs: release/*.uf2 release/*.elf release/*.zip + arch: nrf52840 diff --git a/.github/workflows/build_rpi2040.yml b/.github/workflows/build_rpi2040.yml index b0508877d..492a1f010 100644 --- a/.github/workflows/build_rpi2040.yml +++ b/.github/workflows/build_rpi2040.yml @@ -23,3 +23,4 @@ jobs: artifact-paths: | release/*.uf2 release/*.elf + arch: rp2040 diff --git a/.github/workflows/build_stm32.yml b/.github/workflows/build_stm32.yml index e78178db3..b463bab71 100644 --- a/.github/workflows/build_stm32.yml +++ b/.github/workflows/build_stm32.yml @@ -23,3 +23,5 @@ jobs: artifact-paths: | release/*.hex release/*.bin + release/*.elf + arch: stm32 diff --git a/.github/workflows/main_matrix.yml b/.github/workflows/main_matrix.yml index 277003a61..a69a105a0 100644 --- a/.github/workflows/main_matrix.yml +++ b/.github/workflows/main_matrix.yml @@ -2,9 +2,6 @@ name: CI concurrency: group: ci-${{ github.head_ref || github.run_id }} cancel-in-progress: true -#concurrency: -# group: ${{ github.ref }} -# cancel-in-progress: ${{ github.ref != 'refs/heads/master' }} on: # # Triggers the workflow on push but only for the master branch push: @@ -155,8 +152,13 @@ jobs: permissions: contents: write pull-requests: write + strategy: + fail-fast: false + matrix: + arch: [esp32, esp32s3, esp32c3, esp32c6, nrf52840, rp2040, stm32] runs-on: ubuntu-latest - needs: [ + needs: + [ build-esp32, build-esp32-s3, build-esp32-c3, @@ -164,9 +166,6 @@ jobs: build-nrf52, build-rpi2040, build-stm32, - package-raspbian, - package-raspbian-armv7l, - # package-native, ] steps: - name: Checkout code @@ -178,6 +177,7 @@ jobs: - uses: actions/download-artifact@v4 with: path: ./ + pattern: firmware-${{matrix.arch}}-* merge-multiple: true - name: Display structure of downloaded files @@ -188,12 +188,12 @@ jobs: id: version - name: Move files up - run: mv -b -t ./ ./release/meshtasticd_linux_* ./bin/config-dist.yaml ./bin/device-*.sh ./bin/device-*.bat + run: mv -b -t ./ ./bin/device-*.sh ./bin/device-*.bat - name: Repackage in single firmware zip uses: actions/upload-artifact@v4 with: - name: firmware-${{ steps.version.outputs.version }} + name: firmware-${{matrix.arch}}-${{ steps.version.outputs.version }} overwrite: true path: | ./firmware-*.bin @@ -202,8 +202,6 @@ jobs: ./firmware-*-ota.zip ./device-*.sh ./device-*.bat - ./meshtasticd_linux_* - ./config-dist.yaml ./littlefs-*.bin ./bleota*bin ./Meshtastic_nRF52_factory_erase*.uf2 @@ -211,7 +209,7 @@ jobs: - uses: actions/download-artifact@v4 with: - name: firmware-${{ steps.version.outputs.version }} + name: firmware-${{matrix.arch}}-${{ steps.version.outputs.version }} merge-multiple: true path: ./output @@ -225,12 +223,12 @@ jobs: chmod +x ./output/device-update.sh - name: Zip firmware - run: zip -j -9 -r ./firmware-${{ steps.version.outputs.version }}.zip ./output + run: zip -j -9 -r ./firmware-${{matrix.arch}}-${{ steps.version.outputs.version }}.zip ./output - name: Repackage in single elfs zip uses: actions/upload-artifact@v4 with: - name: debug-elfs-${{ steps.version.outputs.version }}.zip + name: debug-elfs-${{matrix.arch}}-${{ steps.version.outputs.version }}.zip overwrite: true path: ./*.elf retention-days: 30 @@ -238,14 +236,21 @@ jobs: - uses: scruplelesswizard/comment-artifact@main if: ${{ github.event_name == 'pull_request' }} with: - name: firmware-${{ steps.version.outputs.version }} - description: "Download firmware-${{ steps.version.outputs.version }}.zip. This artifact will be available for 90 days from creation" + name: firmware-${{matrix.arch}}-${{ steps.version.outputs.version }} + description: "Download firmware-${{matrix.arch}}-${{ steps.version.outputs.version }}.zip. This artifact will be available for 90 days from creation" github-token: ${{ secrets.GITHUB_TOKEN }} release-artifacts: runs-on: ubuntu-latest if: ${{ github.event_name == 'workflow_dispatch' }} - needs: [gather-artifacts] + outputs: + upload_url: ${{ steps.create_release.outputs.upload_url }} + needs: [ + gather-artifacts, + package-raspbian, + package-raspbian-armv7l, + # package-native, + ] steps: - name: Checkout uses: actions/checkout@v4 @@ -259,36 +264,6 @@ jobs: run: echo "version=$(./bin/buildinfo.py long)" >> $GITHUB_OUTPUT id: version - - uses: actions/download-artifact@v4 - with: - name: firmware-${{ steps.version.outputs.version }} - merge-multiple: true - path: ./output - - - name: Display structure of downloaded files - run: ls -R - - - name: Device scripts permissions - run: | - chmod +x ./output/device-install.sh - chmod +x ./output/device-update.sh - - - name: Zip firmware - run: zip -j -9 -r ./firmware-${{ steps.version.outputs.version }}.zip ./output -x meshtasticd_* - - - uses: actions/download-artifact@v4 - with: - name: debug-elfs-${{ steps.version.outputs.version }}.zip - merge-multiple: true - path: ./elfs - - - name: Zip Elfs - run: zip -j -9 -r ./debug-elfs-${{ steps.version.outputs.version }}.zip ./elfs - - # For diagnostics - - name: Show artifacts - run: ls -lR - - name: Create release uses: actions/create-release@v1 id: create_release @@ -302,32 +277,17 @@ jobs: env: GITHUB_TOKEN: ${{ github.token }} - - name: Add bins to release - uses: actions/upload-release-asset@v1 - env: - GITHUB_TOKEN: ${{ github.token }} - with: - upload_url: ${{ steps.create_release.outputs.upload_url }} - asset_path: ./firmware-${{ steps.version.outputs.version }}.zip - asset_name: firmware-${{ steps.version.outputs.version }}.zip - asset_content_type: application/zip - - - name: Add debug elfs to release - uses: actions/upload-release-asset@v1 - env: - GITHUB_TOKEN: ${{ github.token }} - with: - upload_url: ${{ steps.create_release.outputs.upload_url }} - asset_path: ./debug-elfs-${{ steps.version.outputs.version }}.zip - asset_name: debug-elfs-${{ steps.version.outputs.version }}.zip - asset_content_type: application/zip - - - uses: actions/download-artifact@v4 + - name: Download deb files + uses: actions/download-artifact@v4 with: pattern: meshtasticd_${{ steps.version.outputs.version }}_*.deb merge-multiple: true path: ./output + # For diagnostics + - name: Display structure of downloaded files + run: ls -lR + - name: Add raspbian aarch64 .deb uses: actions/upload-release-asset@v1 env: @@ -369,29 +329,73 @@ jobs: add-paths: | version.properties - - name: Checkout meshtastic/meshtastic.github.io + release-firmware: + strategy: + fail-fast: false + matrix: + arch: [esp32, esp32s3, esp32c3, esp32c6, nrf52840, rp2040, stm32] + runs-on: ubuntu-latest + if: ${{ github.event_name == 'workflow_dispatch' }} + needs: [release-artifacts] + steps: + - name: Checkout uses: actions/checkout@v4 + + - name: Setup Python + uses: actions/setup-python@v5 with: - repository: meshtastic/meshtastic.github.io - token: ${{ secrets.ARTIFACTS_TOKEN }} - path: meshtastic.github.io + python-version: 3.x + + - name: Get release version string + run: echo "version=$(./bin/buildinfo.py long)" >> $GITHUB_OUTPUT + id: version + + - uses: actions/download-artifact@v4 + with: + pattern: firmware-${{matrix.arch}}-${{ steps.version.outputs.version }} + merge-multiple: true + path: ./output - name: Display structure of downloaded files - run: ls -R + run: ls -lR - - name: Extract firmware.zip + - name: Device scripts permissions run: | - unzip ./firmware-${{ steps.version.outputs.version }}.zip -d meshtastic.github.io/firmware-${{ steps.version.outputs.version }} + chmod +x ./output/device-install.sh + chmod +x ./output/device-update.sh + - name: Zip firmware + run: zip -j -9 -r ./firmware-${{matrix.arch}}-${{ steps.version.outputs.version }}.zip ./output + + - uses: actions/download-artifact@v4 + with: + name: debug-elfs-${{matrix.arch}}-${{ steps.version.outputs.version }}.zip + merge-multiple: true + path: ./elfs + + - name: Zip firmware + run: zip -j -9 -r ./debug-elfs-${{matrix.arch}}-${{ steps.version.outputs.version }}.zip ./elfs + + # For diagnostics - name: Display structure of downloaded files - run: ls -R + run: ls -lR - - name: Commit and push changes - run: | - cd meshtastic.github.io - find . -type f -name 'meshtasticd_*' -exec rm -f {} + - git config --global user.name "github-actions[bot]" - git config --global user.email "github-actions[bot]@users.noreply.github.com" - git add . - git commit -m "Add firmware version ${{ steps.version.outputs.version }}" - git push + - name: Add bins to release + uses: actions/upload-release-asset@v1 + env: + GITHUB_TOKEN: ${{ github.token }} + with: + upload_url: ${{needs.release-artifacts.outputs.upload_url}} + asset_path: ./firmware-${{matrix.arch}}-${{ steps.version.outputs.version }}.zip + asset_name: firmware-${{matrix.arch}}-${{ steps.version.outputs.version }}.zip + asset_content_type: application/zip + + - name: Add debug elfs to release + uses: actions/upload-release-asset@v1 + env: + GITHUB_TOKEN: ${{ github.token }} + with: + upload_url: ${{needs.release-artifacts.outputs.upload_url}} + asset_path: ./debug-elfs-${{matrix.arch}}-${{ steps.version.outputs.version }}.zip + asset_name: debug-elfs-${{matrix.arch}}-${{ steps.version.outputs.version }}.zip + asset_content_type: application/zip From 3440c640c378120867c9c1d4c2d921186daf894d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Tue, 1 Oct 2024 13:46:02 +0200 Subject: [PATCH 37/88] keep for 30 days only --- .github/workflows/main_matrix.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/main_matrix.yml b/.github/workflows/main_matrix.yml index a69a105a0..555d4d092 100644 --- a/.github/workflows/main_matrix.yml +++ b/.github/workflows/main_matrix.yml @@ -205,7 +205,7 @@ jobs: ./littlefs-*.bin ./bleota*bin ./Meshtastic_nRF52_factory_erase*.uf2 - retention-days: 90 + retention-days: 30 - uses: actions/download-artifact@v4 with: From 0d175a918c6fe752dd4b68ed36db73de9cb84491 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Tue, 1 Oct 2024 16:02:10 +0200 Subject: [PATCH 38/88] misc library updates and compiler warnings, trunk upgrade --- .trunk/trunk.yaml | 12 ++++++------ arch/esp32/esp32.ini | 4 ++-- arch/esp32/esp32c6.ini | 2 +- arch/portduino/portduino.ini | 2 +- arch/rp2xx0/rp2040.ini | 4 ++-- arch/stm32/stm32.ini | 4 ++-- platformio.ini | 16 ++++++++-------- src/mesh/CryptoEngine.cpp | 1 - src/motion/BMA423Sensor.cpp | 4 ++-- variants/rak4631/platformio.ini | 2 +- 10 files changed, 25 insertions(+), 26 deletions(-) diff --git a/.trunk/trunk.yaml b/.trunk/trunk.yaml index 79cd91af5..9ed720c3f 100644 --- a/.trunk/trunk.yaml +++ b/.trunk/trunk.yaml @@ -1,14 +1,14 @@ version: 0.1 cli: - version: 1.22.5 + version: 1.22.6 plugins: sources: - id: trunk - ref: v1.6.2 + ref: v1.6.3 uri: https://github.com/trunk-io/plugins lint: enabled: - - trufflehog@3.82.5 + - trufflehog@3.82.6 - yamllint@1.35.1 - bandit@1.7.10 - checkov@3.2.255 @@ -16,19 +16,19 @@ lint: - trivy@0.55.2 #- trufflehog@3.63.2-rc0 - taplo@0.9.3 - - ruff@0.6.7 + - ruff@0.6.8 - isort@5.13.2 - markdownlint@0.42.0 - oxipng@9.1.2 - svgo@3.3.2 - - actionlint@1.7.2 + - actionlint@1.7.3 - flake8@7.1.1 - hadolint@2.12.0 - shfmt@3.6.0 - shellcheck@0.10.0 - black@24.8.0 - git-diff-check - - gitleaks@8.19.2 + - gitleaks@8.19.3 - clang-format@16.0.3 - prettier@3.3.3 ignore: diff --git a/arch/esp32/esp32.ini b/arch/esp32/esp32.ini index 13360be78..36d8b9542 100644 --- a/arch/esp32/esp32.ini +++ b/arch/esp32/esp32.ini @@ -2,7 +2,7 @@ [esp32_base] extends = arduino_base custom_esp32_kind = esp32 -platform = platformio/espressif32@6.7.0 +platform = platformio/espressif32@6.9.0 build_src_filter = ${arduino_base.build_src_filter} - - - - - @@ -46,7 +46,7 @@ lib_deps = https://github.com/meshtastic/esp32_https_server.git#23665b3adc080a311dcbb586ed5941b5f94d6ea2 h2zero/NimBLE-Arduino@^1.4.2 https://github.com/dbSuS/libpax.git#7bcd3fcab75037505be9b122ab2b24cc5176b587 - https://github.com/lewisxhe/XPowersLib.git#84b7373faea3118b6c37954d52f98b8a337148d6 + lewisxhe/XPowersLib@^0.2.6 https://github.com/meshtastic/ESP32_Codec2.git#633326c78ac251c059ab3a8c430fcdf25b41672f rweather/Crypto@^0.4.0 diff --git a/arch/esp32/esp32c6.ini b/arch/esp32/esp32c6.ini index 3c2165642..53d7f92ec 100644 --- a/arch/esp32/esp32c6.ini +++ b/arch/esp32/esp32c6.ini @@ -23,7 +23,7 @@ lib_deps = ${arduino_base.lib_deps} ${networking_base.lib_deps} ${environmental_base.lib_deps} - https://github.com/lewisxhe/XPowersLib.git#84b7373faea3118b6c37954d52f98b8a337148d6 + lewisxhe/XPowersLib@^0.2.6 https://github.com/meshtastic/ESP32_Codec2.git#633326c78ac251c059ab3a8c430fcdf25b41672f rweather/Crypto@^0.4.0 diff --git a/arch/portduino/portduino.ini b/arch/portduino/portduino.ini index 30cc190d2..8778c32a0 100644 --- a/arch/portduino/portduino.ini +++ b/arch/portduino/portduino.ini @@ -24,7 +24,7 @@ lib_deps = ${env.lib_deps} ${networking_base.lib_deps} rweather/Crypto@^0.4.0 - https://github.com/lovyan03/LovyanGFX.git#5a39989aa2c9492572255b22f033843ec8900233 + lovyan03/LovyanGFX@^1.1.16 build_flags = ${arduino_base.build_flags} diff --git a/arch/rp2xx0/rp2040.ini b/arch/rp2xx0/rp2040.ini index 5b4ec74d2..8120960fd 100644 --- a/arch/rp2xx0/rp2040.ini +++ b/arch/rp2xx0/rp2040.ini @@ -1,8 +1,8 @@ ; Common settings for rp2040 Processor based targets [rp2040_base] -platform = https://github.com/maxgerhardt/platform-raspberrypi.git#60d6ae81fcc73c34b1493ca9e261695e471bc0c2 +platform = https://github.com/maxgerhardt/platform-raspberrypi.git#9e55f6db5c56b9867c69fe473f388beea4546672 extends = arduino_base -platform_packages = framework-arduinopico@https://github.com/earlephilhower/arduino-pico.git#3.7.2 +platform_packages = framework-arduinopico@https://github.com/earlephilhower/arduino-pico.git#a6ab6e1f95bc1428d667d55ea7173c0744acc03c ; 4.0.2+ board_build.core = earlephilhower board_build.filesystem_size = 0.5m diff --git a/arch/stm32/stm32.ini b/arch/stm32/stm32.ini index 4be290015..715e8aa73 100644 --- a/arch/stm32/stm32.ini +++ b/arch/stm32/stm32.ini @@ -1,7 +1,7 @@ [stm32_base] extends = arduino_base platform = ststm32 -platform_packages = platformio/framework-arduinoststm32@https://github.com/stm32duino/Arduino_Core_STM32.git#361a7fdb67e2a7104e99b4f42a802469eef8b129 +platform_packages = platformio/framework-arduinoststm32@https://github.com/stm32duino/Arduino_Core_STM32.git#ea74156acd823b6d14739f389e6cdc648f8ee36e build_type = release @@ -33,5 +33,5 @@ lib_deps = https://github.com/caveman99/Crypto.git#f61ae26a53f7a2d0ba5511625b8bf8eff3a35d5e lib_ignore = - https://github.com/mathertel/OneButton@~2.6.1 + mathertel/OneButton@~2.6.1 Wire \ No newline at end of file diff --git a/platformio.ini b/platformio.ini index 4c35dbd5c..51e76249f 100644 --- a/platformio.ini +++ b/platformio.ini @@ -82,7 +82,7 @@ build_flags = -Wno-missing-field-initializers -DRADIOLIB_EXCLUDE_LORAWAN=1 -DMESHTASTIC_EXCLUDE_DROPZONE=1 -DMESHTASTIC_EXCLUDE_REMOTEHARDWARE=1 - -DBUILD_EPOCH=$UNIX_TIME + ;-DBUILD_EPOCH=$UNIX_TIME ;-D OLED_PL monitor_speed = 115200 @@ -91,11 +91,11 @@ monitor_filters = direct lib_deps = jgromes/RadioLib@~7.0.2 https://github.com/meshtastic/esp8266-oled-ssd1306.git#e16cee124fe26490cb14880c679321ad8ac89c95 ; ESP8266_SSD1306 - https://github.com/mathertel/OneButton@~2.6.1 ; OneButton library for non-blocking button debounce + mathertel/OneButton@~2.6.1 ; OneButton library for non-blocking button debounce https://github.com/meshtastic/arduino-fsm.git#7db3702bf0cfe97b783d6c72595e3f38e0b19159 https://github.com/meshtastic/TinyGPSPlus.git#71a82db35f3b973440044c476d4bcdc673b104f4 https://github.com/meshtastic/ArduinoThread.git#1ae8778c85d0a2a729f989e0b1e7d7c4dc84eef0 - nanopb/Nanopb@^0.4.8 + nanopb/Nanopb@^0.4.9 erriez/ErriezCRC32@^1.0.1 ; Used for the code analysis in PIO Home / Inspect @@ -128,7 +128,7 @@ lib_deps = ; (not included in native / portduino) [environmental_base] lib_deps = - adafruit/Adafruit BusIO@^1.15.0 + adafruit/Adafruit BusIO@^1.16.1 adafruit/Adafruit Unified Sensor@^1.1.11 adafruit/Adafruit BMP280 Library@^2.6.8 adafruit/Adafruit BMP085 Library@^1.2.4 @@ -141,9 +141,9 @@ lib_deps = adafruit/Adafruit SHTC3 Library@^1.0.0 adafruit/Adafruit LPS2X@^2.0.4 adafruit/Adafruit SHT31 Library@^2.2.2 - adafruit/Adafruit PM25 AQI Sensor@^1.0.6 + adafruit/Adafruit PM25 AQI Sensor@^1.1.1 adafruit/Adafruit MPU6050@^2.2.4 - adafruit/Adafruit LIS3DH@^1.2.4 + adafruit/Adafruit LIS3DH@^1.3.0 adafruit/Adafruit AHTX0@^2.0.5 adafruit/Adafruit LSM6DS@^4.7.2 adafruit/Adafruit VEML7700 Library@^2.1.6 @@ -158,8 +158,8 @@ lib_deps = https://github.com/boschsensortec/Bosch-BSEC2-Library#v1.7.2502 boschsensortec/BME68x Sensor Library@^1.1.40407 https://github.com/KodinLanewave/INA3221@^1.0.1 - lewisxhe/SensorLib@0.2.0 + lewisxhe/SensorLib@^0.2.1 mprograms/QMC5883LCompass@^1.2.0 - https://github.com/meshtastic/DFRobot_LarkWeatherStation#dee914270dc7cb3e43fbf034edd85a63a16a12ee + https://github.com/meshtastic/DFRobot_LarkWeatherStation#4de3a9cadef0f6a5220a8a906cf9775b02b0040d https://github.com/gjelsoe/STK8xxx-Accelerometer.git#v0.1.1 diff --git a/src/mesh/CryptoEngine.cpp b/src/mesh/CryptoEngine.cpp index 085055f41..5c8fdf6ae 100644 --- a/src/mesh/CryptoEngine.cpp +++ b/src/mesh/CryptoEngine.cpp @@ -66,7 +66,6 @@ bool CryptoEngine::encryptCurve25519(uint32_t toNode, uint32_t fromNode, uint64_ uint8_t *bytesOut) { uint8_t *auth; - uint32_t *extraNonce; long extraNonceTmp = random(); auth = bytesOut + numBytes; memcpy((uint8_t *)(auth + 8), &extraNonceTmp, diff --git a/src/motion/BMA423Sensor.cpp b/src/motion/BMA423Sensor.cpp index ec07b7c40..70ddb0624 100755 --- a/src/motion/BMA423Sensor.cpp +++ b/src/motion/BMA423Sensor.cpp @@ -26,9 +26,9 @@ bool BMA423Sensor::init() #ifdef T_WATCH_S3 // Need to raise the wrist function, need to set the correct axis - sensor.setReampAxes(sensor.REMAP_TOP_LAYER_RIGHT_CORNER); + sensor.setRemapAxes(sensor.REMAP_TOP_LAYER_RIGHT_CORNER); #else - sensor.setReampAxes(sensor.REMAP_BOTTOM_LAYER_BOTTOM_LEFT_CORNER); + sensor.setRemapAxes(sensor.REMAP_BOTTOM_LAYER_BOTTOM_LEFT_CORNER); #endif // sensor.enableFeature(sensor.FEATURE_STEP_CNTR, true); sensor.enableFeature(sensor.FEATURE_TILT, true); diff --git a/variants/rak4631/platformio.ini b/variants/rak4631/platformio.ini index 77b5e975c..ced93df66 100644 --- a/variants/rak4631/platformio.ini +++ b/variants/rak4631/platformio.ini @@ -19,7 +19,7 @@ lib_deps = melopero/Melopero RV3028@^1.1.0 https://github.com/RAKWireless/RAK13800-W5100S.git#1.0.2 rakwireless/RAKwireless NCP5623 RGB LED library@^1.0.2 - https://github.com/meshtastic/RAK12034-BMX160.git#4821355fb10390ba8557dc43ca29a023bcfbb9d9 + https://github.com/RAKWireless/RAK12034-BMX160.git#dcead07ffa267d3c906e9ca4a1330ab989e957e2 ; If not set we will default to uploading over serial (first it forces bootloader entry by talking 1200bps to cdcacm) ; Note: as of 6/2013 the serial/bootloader based programming takes approximately 30 seconds From cae2e43dc6b55e3228718f30a7e90463ae055901 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Tue, 1 Oct 2024 16:36:44 +0200 Subject: [PATCH 39/88] revert .... revert .... --- arch/rp2xx0/rp2040.ini | 4 ++-- platformio.ini | 4 ++-- src/motion/BMA423Sensor.cpp | 4 ++-- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/arch/rp2xx0/rp2040.ini b/arch/rp2xx0/rp2040.ini index 8120960fd..5b4ec74d2 100644 --- a/arch/rp2xx0/rp2040.ini +++ b/arch/rp2xx0/rp2040.ini @@ -1,8 +1,8 @@ ; Common settings for rp2040 Processor based targets [rp2040_base] -platform = https://github.com/maxgerhardt/platform-raspberrypi.git#9e55f6db5c56b9867c69fe473f388beea4546672 +platform = https://github.com/maxgerhardt/platform-raspberrypi.git#60d6ae81fcc73c34b1493ca9e261695e471bc0c2 extends = arduino_base -platform_packages = framework-arduinopico@https://github.com/earlephilhower/arduino-pico.git#a6ab6e1f95bc1428d667d55ea7173c0744acc03c ; 4.0.2+ +platform_packages = framework-arduinopico@https://github.com/earlephilhower/arduino-pico.git#3.7.2 board_build.core = earlephilhower board_build.filesystem_size = 0.5m diff --git a/platformio.ini b/platformio.ini index 51e76249f..64d9e7754 100644 --- a/platformio.ini +++ b/platformio.ini @@ -82,7 +82,7 @@ build_flags = -Wno-missing-field-initializers -DRADIOLIB_EXCLUDE_LORAWAN=1 -DMESHTASTIC_EXCLUDE_DROPZONE=1 -DMESHTASTIC_EXCLUDE_REMOTEHARDWARE=1 - ;-DBUILD_EPOCH=$UNIX_TIME + -DBUILD_EPOCH=$UNIX_TIME ;-D OLED_PL monitor_speed = 115200 @@ -158,7 +158,7 @@ lib_deps = https://github.com/boschsensortec/Bosch-BSEC2-Library#v1.7.2502 boschsensortec/BME68x Sensor Library@^1.1.40407 https://github.com/KodinLanewave/INA3221@^1.0.1 - lewisxhe/SensorLib@^0.2.1 + lewisxhe/SensorLib@0.2.0 mprograms/QMC5883LCompass@^1.2.0 https://github.com/meshtastic/DFRobot_LarkWeatherStation#4de3a9cadef0f6a5220a8a906cf9775b02b0040d diff --git a/src/motion/BMA423Sensor.cpp b/src/motion/BMA423Sensor.cpp index 70ddb0624..ec07b7c40 100755 --- a/src/motion/BMA423Sensor.cpp +++ b/src/motion/BMA423Sensor.cpp @@ -26,9 +26,9 @@ bool BMA423Sensor::init() #ifdef T_WATCH_S3 // Need to raise the wrist function, need to set the correct axis - sensor.setRemapAxes(sensor.REMAP_TOP_LAYER_RIGHT_CORNER); + sensor.setReampAxes(sensor.REMAP_TOP_LAYER_RIGHT_CORNER); #else - sensor.setRemapAxes(sensor.REMAP_BOTTOM_LAYER_BOTTOM_LEFT_CORNER); + sensor.setReampAxes(sensor.REMAP_BOTTOM_LAYER_BOTTOM_LEFT_CORNER); #endif // sensor.enableFeature(sensor.FEATURE_STEP_CNTR, true); sensor.enableFeature(sensor.FEATURE_TILT, true); From 5f974d296147343dc8313684f954d450fd629559 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Tue, 1 Oct 2024 21:04:23 +0200 Subject: [PATCH 40/88] save a couple of bytes (#4922) --- variants/rak3172/platformio.ini | 3 +++ variants/rak4631_epaper/platformio.ini | 3 +++ variants/rak4631_epaper_onrxtx/platformio.ini | 3 +++ variants/wio-e5/platformio.ini | 3 +++ 4 files changed, 12 insertions(+) diff --git a/variants/rak3172/platformio.ini b/variants/rak3172/platformio.ini index d1bd55e83..9e617e01e 100644 --- a/variants/rak3172/platformio.ini +++ b/variants/rak3172/platformio.ini @@ -28,4 +28,7 @@ build_flags = -DHAL_TIM_MODULE_DISABLED -DHAL_WWDG_MODULE_DISABLED -DHAL_EXTI_MODULE_DISABLED + -DRADIOLIB_EXCLUDE_SX128X=1 + -DRADIOLIB_EXCLUDE_SX127X=1 + -DRADIOLIB_EXCLUDE_LR11X0=1 upload_port = stlink \ No newline at end of file diff --git a/variants/rak4631_epaper/platformio.ini b/variants/rak4631_epaper/platformio.ini index 08342dcf7..2479f09c8 100644 --- a/variants/rak4631_epaper/platformio.ini +++ b/variants/rak4631_epaper/platformio.ini @@ -7,6 +7,9 @@ build_flags = ${nrf52840_base.build_flags} -Ivariants/rak4631_epaper -D RAK_4631 -DEINK_DISPLAY_MODEL=GxEPD2_213_BN -DEINK_WIDTH=250 -DEINK_HEIGHT=122 + -DRADIOLIB_EXCLUDE_SX128X=1 + -DRADIOLIB_EXCLUDE_SX127X=1 + -DRADIOLIB_EXCLUDE_LR11X0=1 build_src_filter = ${nrf52_base.build_src_filter} +<../variants/rak4631_epaper> lib_deps = ${nrf52840_base.lib_deps} diff --git a/variants/rak4631_epaper_onrxtx/platformio.ini b/variants/rak4631_epaper_onrxtx/platformio.ini index f7035a1b1..8c1b8eee8 100644 --- a/variants/rak4631_epaper_onrxtx/platformio.ini +++ b/variants/rak4631_epaper_onrxtx/platformio.ini @@ -9,6 +9,9 @@ build_flags = ${nrf52840_base.build_flags} -Ivariants/rak4631_epaper -D RAK_4631 -D EINK_DISPLAY_MODEL=GxEPD2_213_BN -D EINK_WIDTH=250 -D EINK_HEIGHT=122 + -D RADIOLIB_EXCLUDE_SX128X=1 + -D RADIOLIB_EXCLUDE_SX127X=1 + -D RADIOLIB_EXCLUDE_LR11X0=1 build_src_filter = ${nrf52_base.build_src_filter} +<../variants/rak4631_epaper_onrxtx> lib_deps = ${nrf52840_base.lib_deps} diff --git a/variants/wio-e5/platformio.ini b/variants/wio-e5/platformio.ini index 51591d569..29c4a0a37 100644 --- a/variants/wio-e5/platformio.ini +++ b/variants/wio-e5/platformio.ini @@ -28,6 +28,9 @@ build_flags = -DHAL_TIM_MODULE_DISABLED -DHAL_WWDG_MODULE_DISABLED -DHAL_EXTI_MODULE_DISABLED + -DRADIOLIB_EXCLUDE_SX128X=1 + -DRADIOLIB_EXCLUDE_SX127X=1 + -DRADIOLIB_EXCLUDE_LR11X0=1 ; -D PIO_FRAMEWORK_ARDUINO_NANOLIB_FLOAT_PRINTF upload_port = stlink \ No newline at end of file From e1e7bbc4206a579a4fd9a0efb2ef82afa8fbd5fd Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Tue, 1 Oct 2024 14:04:44 -0500 Subject: [PATCH 41/88] [create-pull-request] automated change (#4918) Co-authored-by: thebentern <9000580+thebentern@users.noreply.github.com> --- version.properties | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/version.properties b/version.properties index 5f506ee26..f6a385c9f 100644 --- a/version.properties +++ b/version.properties @@ -1,4 +1,4 @@ [VERSION] major = 2 minor = 5 -build = 4 +build = 5 From 18f12584abc9b98963deac6f780b266284062156 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Tue, 1 Oct 2024 15:38:36 -0500 Subject: [PATCH 42/88] Consolidate and shrink down the re-used strings in logs (#4907) * Consolidate and shrink down the re-used strings in GPS * Condense all the things --------- Co-authored-by: GUVWAF --- src/Power.cpp | 2 - src/airtime.cpp | 6 +- src/gps/GPS.cpp | 101 +++++++++--------- src/gps/GPS.h | 2 + src/gps/ubx.h | 4 +- src/mesh/FloodingRouter.cpp | 8 +- src/mesh/MeshService.cpp | 13 ++- src/mesh/NodeDB.cpp | 2 +- src/mesh/RF95Interface.cpp | 12 +-- src/mesh/RadioInterface.cpp | 10 +- src/mesh/RadioLibInterface.cpp | 2 +- src/mesh/RadioLibInterface.h | 2 + src/mesh/ReliableRouter.cpp | 9 +- src/mesh/Router.cpp | 4 +- src/mesh/SX126xInterface.cpp | 18 ++-- src/mesh/SX128xInterface.cpp | 16 +-- src/mesh/http/ContentHandler.cpp | 2 +- src/modules/StoreForwardModule.cpp | 60 +++++------ src/modules/Telemetry/PowerTelemetry.cpp | 2 +- .../Telemetry/Sensor/MAX17048Sensor.cpp | 20 ++-- src/modules/Telemetry/Sensor/MAX17048Sensor.h | 1 + src/modules/TraceRouteModule.cpp | 2 +- src/serialization/MeshPacketSerializer.cpp | 18 ++-- src/serialization/MeshPacketSerializer.h | 1 + 24 files changed, 158 insertions(+), 159 deletions(-) diff --git a/src/Power.cpp b/src/Power.cpp index 6ed937648..2f5f441ae 100644 --- a/src/Power.cpp +++ b/src/Power.cpp @@ -971,7 +971,6 @@ bool Power::axpChipInit() PMU->enableVbusVoltageMeasure(); PMU->enableBattVoltageMeasure(); - LOG_DEBUG("=======================================================================\n"); if (PMU->isChannelAvailable(XPOWERS_DCDC1)) { LOG_DEBUG("DC1 : %s Voltage:%u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC1) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC1)); @@ -1020,7 +1019,6 @@ bool Power::axpChipInit() LOG_DEBUG("BLDO2: %s Voltage:%u mV \n", PMU->isPowerChannelEnable(XPOWERS_BLDO2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_BLDO2)); } - LOG_DEBUG("=======================================================================\n"); // We can safely ignore this approach for most (or all) boards because MCU turned off // earlier than battery discharged to 2.6V. diff --git a/src/airtime.cpp b/src/airtime.cpp index 2702ee2bf..fcda05468 100644 --- a/src/airtime.cpp +++ b/src/airtime.cpp @@ -13,17 +13,17 @@ void AirTime::logAirtime(reportTypes reportType, uint32_t airtime_ms) { if (reportType == TX_LOG) { - LOG_DEBUG("AirTime - Packet transmitted : %ums\n", airtime_ms); + LOG_DEBUG("Packet transmitted : %ums\n", airtime_ms); this->airtimes.periodTX[0] = this->airtimes.periodTX[0] + airtime_ms; air_period_tx[0] = air_period_tx[0] + airtime_ms; this->utilizationTX[this->getPeriodUtilHour()] = this->utilizationTX[this->getPeriodUtilHour()] + airtime_ms; } else if (reportType == RX_LOG) { - LOG_DEBUG("AirTime - Packet received : %ums\n", airtime_ms); + LOG_DEBUG("Packet received : %ums\n", airtime_ms); this->airtimes.periodRX[0] = this->airtimes.periodRX[0] + airtime_ms; air_period_rx[0] = air_period_rx[0] + airtime_ms; } else if (reportType == RX_ALL_LOG) { - LOG_DEBUG("AirTime - Packet received (noise?) : %ums\n", airtime_ms); + LOG_DEBUG("Packet received (noise?) : %ums\n", airtime_ms); this->airtimes.periodRX_ALL[0] = this->airtimes.periodRX_ALL[0] + airtime_ms; } diff --git a/src/gps/GPS.cpp b/src/gps/GPS.cpp index f2b15ba78..33c21c5bb 100644 --- a/src/gps/GPS.cpp +++ b/src/gps/GPS.cpp @@ -530,23 +530,23 @@ bool GPS::setup() _serial_gps->write("$PAIR513*3D\r\n"); // save configuration } else if (gnssModel == GNSS_MODEL_UBLOX6) { clearBuffer(); - SEND_UBX_PACKET(0x06, 0x02, _message_DISABLE_TXT_INFO, "Unable to disable text info messages.\n", 500); - SEND_UBX_PACKET(0x06, 0x39, _message_JAM_6_7, "Unable to enable interference resistance.\n", 500); - SEND_UBX_PACKET(0x06, 0x23, _message_NAVX5, "Unable to configure NAVX5 settings.\n", 500); + SEND_UBX_PACKET(0x06, 0x02, _message_DISABLE_TXT_INFO, "disable text info messages", 500); + SEND_UBX_PACKET(0x06, 0x39, _message_JAM_6_7, "enable interference resistance", 500); + SEND_UBX_PACKET(0x06, 0x23, _message_NAVX5, "configure NAVX5 settings", 500); // Turn off unwanted NMEA messages, set update rate - SEND_UBX_PACKET(0x06, 0x08, _message_1HZ, "Unable to set GPS update rate.\n", 500); - SEND_UBX_PACKET(0x06, 0x01, _message_GLL, "Unable to disable NMEA GLL.\n", 500); - SEND_UBX_PACKET(0x06, 0x01, _message_GSA, "Unable to Enable NMEA GSA.\n", 500); - SEND_UBX_PACKET(0x06, 0x01, _message_GSV, "Unable to disable NMEA GSV.\n", 500); - SEND_UBX_PACKET(0x06, 0x01, _message_VTG, "Unable to disable NMEA VTG.\n", 500); - SEND_UBX_PACKET(0x06, 0x01, _message_RMC, "Unable to enable NMEA RMC.\n", 500); - SEND_UBX_PACKET(0x06, 0x01, _message_GGA, "Unable to enable NMEA GGA.\n", 500); + SEND_UBX_PACKET(0x06, 0x08, _message_1HZ, "set GPS update rate", 500); + SEND_UBX_PACKET(0x06, 0x01, _message_GLL, "disable NMEA GLL", 500); + SEND_UBX_PACKET(0x06, 0x01, _message_GSA, "enable NMEA GSA", 500); + SEND_UBX_PACKET(0x06, 0x01, _message_GSV, "disable NMEA GSV", 500); + SEND_UBX_PACKET(0x06, 0x01, _message_VTG, "disable NMEA VTG", 500); + SEND_UBX_PACKET(0x06, 0x01, _message_RMC, "enable NMEA RMC", 500); + SEND_UBX_PACKET(0x06, 0x01, _message_GGA, "enable NMEA GGA", 500); clearBuffer(); - SEND_UBX_PACKET(0x06, 0x11, _message_CFG_RXM_ECO, "Unable to enable powersaving ECO mode for Neo-6.\n", 500); - SEND_UBX_PACKET(0x06, 0x3B, _message_CFG_PM2, "Unable to enable powersaving details for GPS.\n", 500); - SEND_UBX_PACKET(0x06, 0x01, _message_AID, "Unable to disable UBX-AID.\n", 500); + SEND_UBX_PACKET(0x06, 0x11, _message_CFG_RXM_ECO, "enable powersaving ECO mode for Neo-6", 500); + SEND_UBX_PACKET(0x06, 0x3B, _message_CFG_PM2, "enable powersaving details for GPS", 500); + SEND_UBX_PACKET(0x06, 0x01, _message_AID, "disable UBX-AID", 500); msglen = makeUBXPacket(0x06, 0x09, sizeof(_message_SAVE), _message_SAVE); _serial_gps->write(UBXscratch, msglen); @@ -567,7 +567,7 @@ bool GPS::setup() if (getACK(0x06, 0x3e, 800) == GNSS_RESPONSE_NAK) { // It's not critical if the module doesn't acknowledge this configuration. - LOG_INFO("Unable to reconfigure GNSS - defaults maintained. Is this module GPS-only?\n"); + LOG_INFO("reconfigure GNSS - defaults maintained. Is this module GPS-only?\n"); } else { if (gnssModel == GNSS_MODEL_UBLOX7) { LOG_INFO("GNSS configured for GPS+SBAS.\n"); @@ -581,40 +581,40 @@ bool GPS::setup() // Disable Text Info messages //6,7,8,9 clearBuffer(); - SEND_UBX_PACKET(0x06, 0x02, _message_DISABLE_TXT_INFO, "Unable to disable text info messages.\n", 500); + SEND_UBX_PACKET(0x06, 0x02, _message_DISABLE_TXT_INFO, "disable text info messages", 500); if (gnssModel == GNSS_MODEL_UBLOX8) { // 8 clearBuffer(); - SEND_UBX_PACKET(0x06, 0x39, _message_JAM_8, "Unable to enable interference resistance.\n", 500); + SEND_UBX_PACKET(0x06, 0x39, _message_JAM_8, "enable interference resistance", 500); clearBuffer(); - SEND_UBX_PACKET(0x06, 0x23, _message_NAVX5_8, "Unable to configure NAVX5_8 settings.\n", 500); + SEND_UBX_PACKET(0x06, 0x23, _message_NAVX5_8, "configure NAVX5_8 settings", 500); } else { // 6,7,9 - SEND_UBX_PACKET(0x06, 0x39, _message_JAM_6_7, "Unable to enable interference resistance.\n", 500); - SEND_UBX_PACKET(0x06, 0x23, _message_NAVX5, "Unable to configure NAVX5 settings.\n", 500); + SEND_UBX_PACKET(0x06, 0x39, _message_JAM_6_7, "enable interference resistance", 500); + SEND_UBX_PACKET(0x06, 0x23, _message_NAVX5, "configure NAVX5 settings", 500); } // Turn off unwanted NMEA messages, set update rate - SEND_UBX_PACKET(0x06, 0x08, _message_1HZ, "Unable to set GPS update rate.\n", 500); - SEND_UBX_PACKET(0x06, 0x01, _message_GLL, "Unable to disable NMEA GLL.\n", 500); - SEND_UBX_PACKET(0x06, 0x01, _message_GSA, "Unable to Enable NMEA GSA.\n", 500); - SEND_UBX_PACKET(0x06, 0x01, _message_GSV, "Unable to disable NMEA GSV.\n", 500); - SEND_UBX_PACKET(0x06, 0x01, _message_VTG, "Unable to disable NMEA VTG.\n", 500); - SEND_UBX_PACKET(0x06, 0x01, _message_RMC, "Unable to enable NMEA RMC.\n", 500); - SEND_UBX_PACKET(0x06, 0x01, _message_GGA, "Unable to enable NMEA GGA.\n", 500); + SEND_UBX_PACKET(0x06, 0x08, _message_1HZ, "set GPS update rate", 500); + SEND_UBX_PACKET(0x06, 0x01, _message_GLL, "disable NMEA GLL", 500); + SEND_UBX_PACKET(0x06, 0x01, _message_GSA, "enable NMEA GSA", 500); + SEND_UBX_PACKET(0x06, 0x01, _message_GSV, "disable NMEA GSV", 500); + SEND_UBX_PACKET(0x06, 0x01, _message_VTG, "disable NMEA VTG", 500); + SEND_UBX_PACKET(0x06, 0x01, _message_RMC, "enable NMEA RMC", 500); + SEND_UBX_PACKET(0x06, 0x01, _message_GGA, "enable NMEA GGA", 500); if (uBloxProtocolVersion >= 18) { clearBuffer(); - SEND_UBX_PACKET(0x06, 0x86, _message_PMS, "Unable to enable powersaving for GPS.\n", 500); - SEND_UBX_PACKET(0x06, 0x3B, _message_CFG_PM2, "Unable to enable powersaving details for GPS.\n", 500); + SEND_UBX_PACKET(0x06, 0x86, _message_PMS, "enable powersaving for GPS", 500); + SEND_UBX_PACKET(0x06, 0x3B, _message_CFG_PM2, "enable powersaving details for GPS", 500); // For M8 we want to enable NMEA vserion 4.10 so we can see the additional sats. if (gnssModel == GNSS_MODEL_UBLOX8) { clearBuffer(); - SEND_UBX_PACKET(0x06, 0x17, _message_NMEA, "Unable to enable NMEA 4.10.\n", 500); + SEND_UBX_PACKET(0x06, 0x17, _message_NMEA, "enable NMEA 4.10", 500); } } else { - SEND_UBX_PACKET(0x06, 0x11, _message_CFG_RXM_PSM, "Unable to enable powersaving mode for GPS.\n", 500); - SEND_UBX_PACKET(0x06, 0x3B, _message_CFG_PM2, "Unable to enable powersaving details for GPS.\n", 500); + SEND_UBX_PACKET(0x06, 0x11, _message_CFG_RXM_PSM, "enable powersaving mode for GPS", 500); + SEND_UBX_PACKET(0x06, 0x3B, _message_CFG_PM2, "enable powersaving details for GPS", 500); } msglen = makeUBXPacket(0x06, 0x09, sizeof(_message_SAVE), _message_SAVE); @@ -627,40 +627,38 @@ bool GPS::setup() } else if (gnssModel == GNSS_MODEL_UBLOX10) { delay(1000); clearBuffer(); - SEND_UBX_PACKET(0x06, 0x8A, _message_VALSET_DISABLE_NMEA_RAM, "Unable to disable NMEA messages in M10 RAM.\n", 300); + SEND_UBX_PACKET(0x06, 0x8A, _message_VALSET_DISABLE_NMEA_RAM, "disable NMEA messages in M10 RAM", 300); delay(750); clearBuffer(); - SEND_UBX_PACKET(0x06, 0x8A, _message_VALSET_DISABLE_NMEA_BBR, "Unable to disable NMEA messages in M10 BBR.\n", 300); + SEND_UBX_PACKET(0x06, 0x8A, _message_VALSET_DISABLE_NMEA_BBR, "disable NMEA messages in M10 BBR", 300); delay(750); clearBuffer(); - SEND_UBX_PACKET(0x06, 0x8A, _message_VALSET_DISABLE_TXT_INFO_RAM, - "Unable to disable Info messages for M10 GPS RAM.\n", 300); + SEND_UBX_PACKET(0x06, 0x8A, _message_VALSET_DISABLE_TXT_INFO_RAM, "disable Info messages for M10 GPS RAM", 300); delay(750); // Next disable Info txt messages in BBR layer clearBuffer(); - SEND_UBX_PACKET(0x06, 0x8A, _message_VALSET_DISABLE_TXT_INFO_BBR, - "Unable to disable Info messages for M10 GPS BBR.\n", 300); + SEND_UBX_PACKET(0x06, 0x8A, _message_VALSET_DISABLE_TXT_INFO_BBR, "disable Info messages for M10 GPS BBR", 300); delay(750); // Do M10 configuration for Power Management. - SEND_UBX_PACKET(0x06, 0x8A, _message_VALSET_PM_RAM, "Unable to enable powersaving for M10 GPS RAM.\n", 300); + SEND_UBX_PACKET(0x06, 0x8A, _message_VALSET_PM_RAM, "enable powersaving for M10 GPS RAM", 300); delay(750); - SEND_UBX_PACKET(0x06, 0x8A, _message_VALSET_PM_BBR, "Unable to enable powersaving for M10 GPS BBR.\n", 300); + SEND_UBX_PACKET(0x06, 0x8A, _message_VALSET_PM_BBR, "enable powersaving for M10 GPS BBR", 300); delay(750); - SEND_UBX_PACKET(0x06, 0x8A, _message_VALSET_ITFM_RAM, "Unable to enable Jamming detection M10 GPS RAM.\n", 300); + SEND_UBX_PACKET(0x06, 0x8A, _message_VALSET_ITFM_RAM, "enable Jamming detection M10 GPS RAM", 300); delay(750); - SEND_UBX_PACKET(0x06, 0x8A, _message_VALSET_ITFM_BBR, "Unable to enable Jamming detection M10 GPS BBR.\n", 300); + SEND_UBX_PACKET(0x06, 0x8A, _message_VALSET_ITFM_BBR, "enable Jamming detection M10 GPS BBR", 300); delay(750); // Here is where the init commands should go to do further M10 initialization. - SEND_UBX_PACKET(0x06, 0x8A, _message_VALSET_DISABLE_SBAS_RAM, "Unable to disable SBAS M10 GPS RAM.\n", 300); + SEND_UBX_PACKET(0x06, 0x8A, _message_VALSET_DISABLE_SBAS_RAM, "disable SBAS M10 GPS RAM", 300); delay(750); // will cause a receiver restart so wait a bit - SEND_UBX_PACKET(0x06, 0x8A, _message_VALSET_DISABLE_SBAS_BBR, "Unable to disable SBAS M10 GPS BBR.\n", 300); + SEND_UBX_PACKET(0x06, 0x8A, _message_VALSET_DISABLE_SBAS_BBR, "disable SBAS M10 GPS BBR", 300); delay(750); // will cause a receiver restart so wait a bit // Done with initialization, Now enable wanted NMEA messages in BBR layer so they will survive a periodic sleep. - SEND_UBX_PACKET(0x06, 0x8A, _message_VALSET_ENABLE_NMEA_BBR, "Unable to enable messages for M10 GPS BBR.\n", 300); + SEND_UBX_PACKET(0x06, 0x8A, _message_VALSET_ENABLE_NMEA_BBR, "enable messages for M10 GPS BBR", 300); delay(750); // Next enable wanted NMEA messages in RAM layer - SEND_UBX_PACKET(0x06, 0x8A, _message_VALSET_ENABLE_NMEA_RAM, "Unable to enable messages for M10 GPS RAM.\n", 500); + SEND_UBX_PACKET(0x06, 0x8A, _message_VALSET_ENABLE_NMEA_RAM, "enable messages for M10 GPS RAM", 500); delay(750); // As the M10 has no flash, the best we can do to preserve the config is to set it in RAM and BBR. @@ -1073,12 +1071,15 @@ int GPS::prepareDeepSleep(void *unused) return 0; } +const char *PROBE_MESSAGE = "Trying %s (%s)...\n"; +const char *DETECTED_MESSAGE = "%s detected, using %s Module\n"; + #define PROBE_SIMPLE(CHIP, TOWRITE, RESPONSE, DRIVER, TIMEOUT, ...) \ - LOG_DEBUG("Trying " TOWRITE " (" CHIP ") ...\n"); \ + LOG_DEBUG(PROBE_MESSAGE, TOWRITE, CHIP); \ clearBuffer(); \ _serial_gps->write(TOWRITE "\r\n"); \ if (getACK(RESPONSE, TIMEOUT) == GNSS_RESPONSE_OK) { \ - LOG_INFO(CHIP " detected, using " #DRIVER " Module\n"); \ + LOG_INFO(DETECTED_MESSAGE, CHIP, #DRIVER); \ return DRIVER; \ } @@ -1367,21 +1368,21 @@ bool GPS::factoryReset() 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x02, 0x1C, 0xA2}; _serial_gps->write(_message_reset1, sizeof(_message_reset1)); if (getACK(0x05, 0x01, 10000)) { - LOG_INFO("Get ack success!\n"); + LOG_INFO(ACK_SUCCESS_MESSAGE); } delay(100); byte _message_reset2[] = {0xB5, 0x62, 0x06, 0x09, 0x0D, 0x00, 0xFF, 0xFF, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x1B, 0xA1}; _serial_gps->write(_message_reset2, sizeof(_message_reset2)); if (getACK(0x05, 0x01, 10000)) { - LOG_INFO("Get ack success!\n"); + LOG_INFO(ACK_SUCCESS_MESSAGE); } delay(100); byte _message_reset3[] = {0xB5, 0x62, 0x06, 0x09, 0x0D, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xFF, 0xFF, 0x00, 0x00, 0x03, 0x1D, 0xB3}; _serial_gps->write(_message_reset3, sizeof(_message_reset3)); if (getACK(0x05, 0x01, 10000)) { - LOG_INFO("Get ack success!\n"); + LOG_INFO(ACK_SUCCESS_MESSAGE); } // Reset device ram to COLDSTART state // byte _message_CFG_RST_COLDSTART[] = {0xB5, 0x62, 0x06, 0x04, 0x04, 0x00, 0xFF, 0xB9, 0x00, 0x00, 0xC6, 0x8B}; diff --git a/src/gps/GPS.h b/src/gps/GPS.h index 317d80544..6222881bc 100644 --- a/src/gps/GPS.h +++ b/src/gps/GPS.h @@ -156,6 +156,8 @@ class GPS : private concurrency::OSThread static const uint8_t _message_CAS_CFG_NAVX_CONF[]; static const uint8_t _message_CAS_CFG_RATE_1HZ[]; + const char *ACK_SUCCESS_MESSAGE = "Get ack success!\n"; + meshtastic_Position p = meshtastic_Position_init_default; /** This is normally bound to config.position.gps_en_gpio but some rare boards (like heltec tracker) need more advanced diff --git a/src/gps/ubx.h b/src/gps/ubx.h index c73a7efb3..b137d3349 100644 --- a/src/gps/ubx.h +++ b/src/gps/ubx.h @@ -1,8 +1,10 @@ +const char *failMessage = "Unable to %s\n"; + #define SEND_UBX_PACKET(TYPE, ID, DATA, ERRMSG, TIMEOUT) \ msglen = makeUBXPacket(TYPE, ID, sizeof(DATA), DATA); \ _serial_gps->write(UBXscratch, msglen); \ if (getACK(TYPE, ID, TIMEOUT) != GNSS_RESPONSE_OK) { \ - LOG_WARN(#ERRMSG); \ + LOG_WARN(failMessage, #ERRMSG); \ } // Power Management diff --git a/src/mesh/FloodingRouter.cpp b/src/mesh/FloodingRouter.cpp index fbe56159c..e2dbd8997 100644 --- a/src/mesh/FloodingRouter.cpp +++ b/src/mesh/FloodingRouter.cpp @@ -21,7 +21,7 @@ ErrorCode FloodingRouter::send(meshtastic_MeshPacket *p) bool FloodingRouter::shouldFilterReceived(const meshtastic_MeshPacket *p) { if (wasSeenRecently(p)) { // Note: this will also add a recent packet record - printPacket("Ignoring incoming msg we've already seen", p); + printPacket("Ignoring dupe incoming msg", p); if (config.device.role != meshtastic_Config_DeviceConfig_Role_ROUTER && config.device.role != meshtastic_Config_DeviceConfig_Role_REPEATER) { // cancel rebroadcast of this message *if* there was already one, unless we're a router/repeater! @@ -38,7 +38,7 @@ void FloodingRouter::sniffReceived(const meshtastic_MeshPacket *p, const meshtas bool isAckorReply = (p->which_payload_variant == meshtastic_MeshPacket_decoded_tag) && (p->decoded.request_id != 0); if (isAckorReply && p->to != getNodeNum() && p->to != NODENUM_BROADCAST) { // do not flood direct message that is ACKed or replied to - LOG_DEBUG("Receiving an ACK or reply not for me, but don't need to rebroadcast this direct message anymore.\n"); + LOG_DEBUG("Rxd an ACK/reply not for me, cancel rebroadcast.\n"); Router::cancelSending(p->to, p->decoded.request_id); // cancel rebroadcast for this DM } if ((p->to != getNodeNum()) && (p->hop_limit > 0) && (getFrom(p) != getNodeNum())) { @@ -55,7 +55,7 @@ void FloodingRouter::sniffReceived(const meshtastic_MeshPacket *p, const meshtas } #endif - LOG_INFO("Rebroadcasting received floodmsg to neighbors\n"); + LOG_INFO("Rebroadcasting received floodmsg\n"); // Note: we are careful to resend using the original senders node id // We are careful not to call our hooked version of send() - because we don't want to check this again Router::send(tosend); @@ -63,7 +63,7 @@ void FloodingRouter::sniffReceived(const meshtastic_MeshPacket *p, const meshtas LOG_DEBUG("Not rebroadcasting. Role = Role_ClientMute\n"); } } else { - LOG_DEBUG("Ignoring a simple (0 id) broadcast\n"); + LOG_DEBUG("Ignoring 0 id broadcast\n"); } } // handle the packet as normal diff --git a/src/mesh/MeshService.cpp b/src/mesh/MeshService.cpp index ac97d51a7..a8a207352 100644 --- a/src/mesh/MeshService.cpp +++ b/src/mesh/MeshService.cpp @@ -80,12 +80,11 @@ int MeshService::handleFromRadio(const meshtastic_MeshPacket *mp) nodeDB->updateFrom(*mp); // update our DB state based off sniffing every RX packet from the radio if (mp->which_payload_variant == meshtastic_MeshPacket_decoded_tag && mp->decoded.portnum == meshtastic_PortNum_TELEMETRY_APP && mp->decoded.request_id > 0) { - LOG_DEBUG( - "Received telemetry response. Skip sending our NodeInfo because this potentially a Repeater which will ignore our " - "request for its NodeInfo.\n"); + LOG_DEBUG("Received telemetry response. Skip sending our NodeInfo.\n"); // because this potentially a Repeater which will + // ignore our request for its NodeInfo } else if (mp->which_payload_variant == meshtastic_MeshPacket_decoded_tag && !nodeDB->getMeshNode(mp->from)->has_user && nodeInfoModule) { - LOG_INFO("Heard a node on channel %d we don't know, sending NodeInfo and asking for a response.\n", mp->channel); + LOG_INFO("Heard new node on channel %d, sending NodeInfo and asking for a response.\n", mp->channel); if (airTime->isTxAllowedChannelUtil(true)) { nodeInfoModule->sendOurNodeInfo(mp->from, true, mp->channel); } else { @@ -223,7 +222,7 @@ ErrorCode MeshService::sendQueueStatusToPhone(const meshtastic_QueueStatus &qs, copied->mesh_packet_id = mesh_packet_id; if (toPhoneQueueStatusQueue.numFree() == 0) { - LOG_DEBUG("NOTE: tophone queue status queue is full, discarding oldest\n"); + LOG_INFO("tophone queue status queue is full, discarding oldest\n"); meshtastic_QueueStatus *d = toPhoneQueueStatusQueue.dequeuePtr(0); if (d) releaseQueueStatusToPool(d); @@ -317,7 +316,7 @@ void MeshService::sendToPhone(meshtastic_MeshPacket *p) void MeshService::sendMqttMessageToClientProxy(meshtastic_MqttClientProxyMessage *m) { - LOG_DEBUG("Sending mqtt message on topic '%s' to client for proxying to server\n", m->topic); + LOG_DEBUG("Sending mqtt message on topic '%s' to client for proxy\n", m->topic); if (toPhoneMqttProxyQueue.numFree() == 0) { LOG_WARN("MqttClientProxyMessagePool queue is full, discarding oldest\n"); meshtastic_MqttClientProxyMessage *d = toPhoneMqttProxyQueue.dequeuePtr(0); @@ -407,4 +406,4 @@ int MeshService::onGPSChanged(const meshtastic::GPSStatus *newStatus) bool MeshService::isToPhoneQueueEmpty() { return toPhoneQueue.isEmpty(); -} +} \ No newline at end of file diff --git a/src/mesh/NodeDB.cpp b/src/mesh/NodeDB.cpp index 36b9f3ff4..b78827e65 100644 --- a/src/mesh/NodeDB.cpp +++ b/src/mesh/NodeDB.cpp @@ -1079,7 +1079,7 @@ bool NodeDB::updateUser(uint32_t nodeId, meshtastic_User &p, uint8_t channelInde // We just changed something about the user, store our DB Throttle::execute( &lastNodeDbSave, ONE_MINUTE_MS, []() { nodeDB->saveToDisk(SEGMENT_DEVICESTATE); }, - []() { LOG_DEBUG("Deferring NodeDB saveToDisk for now, since we saved less than a minute ago\n"); }); + []() { LOG_DEBUG("Deferring NodeDB saveToDisk for now\n"); }); // since we saved less than a minute ago } return changed; diff --git a/src/mesh/RF95Interface.cpp b/src/mesh/RF95Interface.cpp index 3cb6bfdda..581fd9034 100644 --- a/src/mesh/RF95Interface.cpp +++ b/src/mesh/RF95Interface.cpp @@ -220,17 +220,17 @@ bool RF95Interface::reconfigure() err = lora->setSyncWord(syncWord); if (err != RADIOLIB_ERR_NONE) - LOG_ERROR("Radiolib error %d when attempting RF95 setSyncWord!\n", err); + LOG_ERROR("RF95 setSyncWord %s%d\n", radioLibErr, err); assert(err == RADIOLIB_ERR_NONE); err = lora->setCurrentLimit(currentLimit); if (err != RADIOLIB_ERR_NONE) - LOG_ERROR("Radiolib error %d when attempting RF95 setCurrentLimit!\n", err); + LOG_ERROR("RF95 setCurrentLimit %s%d\n", radioLibErr, err); assert(err == RADIOLIB_ERR_NONE); err = lora->setPreambleLength(preambleLength); if (err != RADIOLIB_ERR_NONE) - LOG_ERROR("Radiolib error %d when attempting RF95 setPreambleLength!\n", err); + LOG_ERROR(" RF95 setPreambleLength %s%d\n", radioLibErr, err); assert(err == RADIOLIB_ERR_NONE); err = lora->setFrequency(getFreq()); @@ -266,7 +266,7 @@ void RF95Interface::setStandby() { int err = lora->standby(); if (err != RADIOLIB_ERR_NONE) - LOG_ERROR("Radiolib error %d when attempting RF95 standby!\n", err); + LOG_ERROR("RF95 standby %s%d\n", radioLibErr, err); assert(err == RADIOLIB_ERR_NONE); isReceiving = false; // If we were receiving, not any more @@ -290,7 +290,7 @@ void RF95Interface::startReceive() setStandby(); int err = lora->startReceive(); if (err != RADIOLIB_ERR_NONE) - LOG_ERROR("Radiolib error %d when attempting RF95 startReceive!\n", err); + LOG_ERROR("RF95 startReceive %s%d\n", radioLibErr, err); assert(err == RADIOLIB_ERR_NONE); isReceiving = true; @@ -312,7 +312,7 @@ bool RF95Interface::isChannelActive() return true; } if (result != RADIOLIB_CHANNEL_FREE) - LOG_ERROR("Radiolib error %d when attempting RF95 isChannelActive!\n", result); + LOG_ERROR("RF95 isChannelActive %s%d\n", radioLibErr, result); assert(result != RADIOLIB_ERR_WRONG_MODEM); // LOG_DEBUG("Channel is free!\n"); diff --git a/src/mesh/RadioInterface.cpp b/src/mesh/RadioInterface.cpp index 683ae7e01..b915f94bd 100644 --- a/src/mesh/RadioInterface.cpp +++ b/src/mesh/RadioInterface.cpp @@ -202,8 +202,6 @@ uint32_t RadioInterface::getPacketTime(uint32_t pl) uint32_t msecs = tPacket * 1000; - LOG_DEBUG("(bw=%d, sf=%d, cr=4/%d) packet symLen=%d ms, payloadSize=%u, time %d ms\n", (int)bw, sf, cr, (int)(tSym * 1000), - pl, msecs); return msecs; } @@ -550,11 +548,11 @@ void RadioInterface::applyModemConfig() LOG_INFO("Radio freq=%.3f, config.lora.frequency_offset=%.3f\n", freq, loraConfig.frequency_offset); LOG_INFO("Set radio: region=%s, name=%s, config=%u, ch=%d, power=%d\n", myRegion->name, channelName, loraConfig.modem_preset, channel_num, power); - LOG_INFO("Radio myRegion->freqStart -> myRegion->freqEnd: %f -> %f (%f MHz)\n", myRegion->freqStart, myRegion->freqEnd, + LOG_INFO("myRegion->freqStart -> myRegion->freqEnd: %f -> %f (%f MHz)\n", myRegion->freqStart, myRegion->freqEnd, myRegion->freqEnd - myRegion->freqStart); - LOG_INFO("Radio myRegion->numChannels: %d x %.3fkHz\n", numChannels, bw); - LOG_INFO("Radio channel_num: %d\n", channel_num + 1); - LOG_INFO("Radio frequency: %f\n", getFreq()); + LOG_INFO("numChannels: %d x %.3fkHz\n", numChannels, bw); + LOG_INFO("channel_num: %d\n", channel_num + 1); + LOG_INFO("frequency: %f\n", getFreq()); LOG_INFO("Slot time: %u msec\n", slotTimeMsec); } diff --git a/src/mesh/RadioLibInterface.cpp b/src/mesh/RadioLibInterface.cpp index 664709ed1..807c8aa02 100644 --- a/src/mesh/RadioLibInterface.cpp +++ b/src/mesh/RadioLibInterface.cpp @@ -466,7 +466,7 @@ void RadioLibInterface::startSend(meshtastic_MeshPacket *txp) { printPacket("Starting low level send", txp); if (disabled || !config.lora.tx_enabled) { - LOG_WARN("startSend is dropping tx packet because we are disabled\n"); + LOG_WARN("Drop Tx packet because LoRa Tx disabled\n"); packetPool.release(txp); } else { configHardwareForSend(); // must be after setStandby diff --git a/src/mesh/RadioLibInterface.h b/src/mesh/RadioLibInterface.h index 13bef851a..090c03046 100644 --- a/src/mesh/RadioLibInterface.h +++ b/src/mesh/RadioLibInterface.h @@ -196,4 +196,6 @@ class RadioLibInterface : public RadioInterface, protected concurrency::Notified * Subclasses must override, implement and then call into this base class implementation */ virtual void setStandby(); + + const char *radioLibErr = "RadioLib err=\n"; }; \ No newline at end of file diff --git a/src/mesh/ReliableRouter.cpp b/src/mesh/ReliableRouter.cpp index 1f2c01473..9482f4185 100644 --- a/src/mesh/ReliableRouter.cpp +++ b/src/mesh/ReliableRouter.cpp @@ -107,12 +107,12 @@ void ReliableRouter::sniffReceived(const meshtastic_MeshPacket *p, const meshtas if (p->to == ourNode) { // ignore ack/nak/want_ack packets that are not address to us (we only handle 0 hop reliability) if (p->want_ack) { if (MeshModule::currentReply) { - LOG_DEBUG("Some other module has replied to this message, no need for a 2nd ack\n"); + LOG_DEBUG("Another module replied to this message, no need for 2nd ack\n"); } else if (p->which_payload_variant == meshtastic_MeshPacket_decoded_tag) { sendAckNak(meshtastic_Routing_Error_NONE, getFrom(p), p->id, p->channel, p->hop_start, p->hop_limit); } else if (p->which_payload_variant == meshtastic_MeshPacket_encrypted_tag && p->channel == 0 && (nodeDB->getMeshNode(p->from) == nullptr || nodeDB->getMeshNode(p->from)->user.public_key.size == 0)) { - LOG_INFO("This looks like it might be a PKI packet from an unknown node, so send PKI_UNKNOWN_PUBKEY\n"); + LOG_INFO("PKI packet from unknown node, send PKI_UNKNOWN_PUBKEY\n"); sendAckNak(meshtastic_Routing_Error_PKI_UNKNOWN_PUBKEY, getFrom(p), p->id, channels.getPrimaryIndex(), p->hop_start, p->hop_limit); } else { @@ -124,7 +124,7 @@ void ReliableRouter::sniffReceived(const meshtastic_MeshPacket *p, const meshtas if (p->which_payload_variant == meshtastic_MeshPacket_decoded_tag && c && c->error_reason == meshtastic_Routing_Error_PKI_UNKNOWN_PUBKEY) { if (owner.public_key.size == 32) { - LOG_INFO("This seems like a remote PKI decrypt failure, so send a NodeInfo"); + LOG_INFO("PKI decrypt failure, send a NodeInfo"); nodeInfoModule->sendOurNodeInfo(p->from, false, p->channel, true); } } @@ -136,11 +136,10 @@ void ReliableRouter::sniffReceived(const meshtastic_MeshPacket *p, const meshtas // We intentionally don't check wasSeenRecently, because it is harmless to delete non existent retransmission records if (ackId || nakId) { + LOG_DEBUG("Received a %s for 0x%x, stopping retransmissions\n", ackId ? "ACK" : "NAK", ackId); if (ackId) { - LOG_DEBUG("Received an ack for 0x%x, stopping retransmissions\n", ackId); stopRetransmission(p->to, ackId); } else { - LOG_DEBUG("Received a nak for 0x%x, stopping retransmissions\n", nakId); stopRetransmission(p->to, nakId); } } diff --git a/src/mesh/Router.cpp b/src/mesh/Router.cpp index bb04b66ac..610d5303e 100644 --- a/src/mesh/Router.cpp +++ b/src/mesh/Router.cpp @@ -503,8 +503,8 @@ meshtastic_Routing_Error perhapsEncode(meshtastic_MeshPacket *p) return meshtastic_Routing_Error_TOO_LARGE; if (p->pki_encrypted && !memfll(p->public_key.bytes, 0, 32) && memcmp(p->public_key.bytes, node->user.public_key.bytes, 32) != 0) { - LOG_WARN("Client public key for client differs from requested! Requested 0x%02x, but stored key begins 0x%02x\n", - *p->public_key.bytes, *node->user.public_key.bytes); + LOG_WARN("Client public key differs from requested: 0x%02x, stored key begins 0x%02x\n", *p->public_key.bytes, + *node->user.public_key.bytes); return meshtastic_Routing_Error_PKI_FAILED; } crypto->encryptCurve25519(p->to, getFrom(p), p->id, numbytes, bytes, ScratchEncrypted); diff --git a/src/mesh/SX126xInterface.cpp b/src/mesh/SX126xInterface.cpp index a23c1e457..924cdfa9f 100644 --- a/src/mesh/SX126xInterface.cpp +++ b/src/mesh/SX126xInterface.cpp @@ -203,17 +203,17 @@ template bool SX126xInterface::reconfigure() err = lora.setSyncWord(syncWord); if (err != RADIOLIB_ERR_NONE) - LOG_ERROR("Radiolib error %d when attempting SX126X setSyncWord!\n", err); + LOG_ERROR("SX126X setSyncWord %s%d\n", radioLibErr, err); assert(err == RADIOLIB_ERR_NONE); err = lora.setCurrentLimit(currentLimit); if (err != RADIOLIB_ERR_NONE) - LOG_ERROR("Radiolib error %d when attempting SX126X setCurrentLimit!\n", err); + LOG_ERROR("SX126X setCurrentLimit %s%d\n", radioLibErr, err); assert(err == RADIOLIB_ERR_NONE); err = lora.setPreambleLength(preambleLength); if (err != RADIOLIB_ERR_NONE) - LOG_ERROR("Radiolib error %d when attempting SX126X setPreambleLength!\n", err); + LOG_ERROR("SX126X setPreambleLength %s%d\n", radioLibErr, err); assert(err == RADIOLIB_ERR_NONE); err = lora.setFrequency(getFreq()); @@ -225,7 +225,7 @@ template bool SX126xInterface::reconfigure() err = lora.setOutputPower(power); if (err != RADIOLIB_ERR_NONE) - LOG_ERROR("Radiolib error %d when attempting SX126X setOutputPower!\n", err); + LOG_ERROR("SX126X setOutputPower %s%d\n", radioLibErr, err); assert(err == RADIOLIB_ERR_NONE); startReceive(); // restart receiving @@ -245,7 +245,7 @@ template void SX126xInterface::setStandby() int err = lora.standby(); if (err != RADIOLIB_ERR_NONE) - LOG_DEBUG("SX126x standby failed with error %d\n", err); + LOG_DEBUG("SX126x standby %s%d\n", radioLibErr, err); assert(err == RADIOLIB_ERR_NONE); isReceiving = false; // If we were receiving, not any more @@ -287,7 +287,7 @@ template void SX126xInterface::startReceive() // Furthermore, we need the PREAMBLE_DETECTED and HEADER_VALID IRQ flag to detect whether we are actively receiving int err = lora.startReceiveDutyCycleAuto(preambleLength, 8, RADIOLIB_IRQ_RX_DEFAULT_FLAGS | RADIOLIB_IRQ_PREAMBLE_DETECTED); if (err != RADIOLIB_ERR_NONE) - LOG_ERROR("Radiolib error %d when attempting SX126X startReceiveDutyCycleAuto!\n", err); + LOG_ERROR("SX126X startReceiveDutyCycleAuto %s%d\n", radioLibErr, err); assert(err == RADIOLIB_ERR_NONE); RadioLibInterface::startReceive(); @@ -308,7 +308,7 @@ template bool SX126xInterface::isChannelActive() if (result == RADIOLIB_LORA_DETECTED) return true; if (result != RADIOLIB_CHANNEL_FREE) - LOG_ERROR("Radiolib error %d when attempting SX126X scanChannel!\n", result); + LOG_ERROR("SX126X scanChannel %s%d\n", radioLibErr, result); assert(result != RADIOLIB_ERR_WRONG_MODEM); return false; @@ -326,8 +326,8 @@ template bool SX126xInterface::sleep() { // Not keeping config is busted - next time nrf52 board boots lora sending fails tcxo related? - see datasheet // \todo Display actual typename of the adapter, not just `SX126x` - LOG_DEBUG("SX126x entering sleep mode (FIXME, don't keep config)\n"); - setStandby(); // Stop any pending operations + LOG_DEBUG("SX126x entering sleep mode\n"); // (FIXME, don't keep config) + setStandby(); // Stop any pending operations // turn off TCXO if it was powered // FIXME - this isn't correct diff --git a/src/mesh/SX128xInterface.cpp b/src/mesh/SX128xInterface.cpp index 2a1bb4e41..d379f26e6 100644 --- a/src/mesh/SX128xInterface.cpp +++ b/src/mesh/SX128xInterface.cpp @@ -129,12 +129,12 @@ template bool SX128xInterface::reconfigure() err = lora.setSyncWord(syncWord); if (err != RADIOLIB_ERR_NONE) - LOG_ERROR("Radiolib error %d when attempting SX128X setSyncWord!\n", err); + LOG_ERROR("SX128X setSyncWord %s%d\n", radioLibErr, err); assert(err == RADIOLIB_ERR_NONE); err = lora.setPreambleLength(preambleLength); if (err != RADIOLIB_ERR_NONE) - LOG_ERROR("Radiolib error %d when attempting SX128X setPreambleLength!\n", err); + LOG_ERROR("SX128X setPreambleLength %s%d\n", radioLibErr, err); assert(err == RADIOLIB_ERR_NONE); err = lora.setFrequency(getFreq()); @@ -146,7 +146,7 @@ template bool SX128xInterface::reconfigure() err = lora.setOutputPower(power); if (err != RADIOLIB_ERR_NONE) - LOG_ERROR("Radiolib error %d when attempting SX128X setOutputPower!\n", err); + LOG_ERROR("SX128X setOutputPower %s%d\n", radioLibErr, err); assert(err == RADIOLIB_ERR_NONE); startReceive(); // restart receiving @@ -171,7 +171,7 @@ template void SX128xInterface::setStandby() int err = lora.standby(); if (err != RADIOLIB_ERR_NONE) - LOG_ERROR("SX128x standby failed with error %d\n", err); + LOG_ERROR("SX128x standby %s%d\n", radioLibErr, err); assert(err == RADIOLIB_ERR_NONE); #if ARCH_PORTDUINO if (settingsMap[rxen] != RADIOLIB_NC) { @@ -261,7 +261,7 @@ template void SX128xInterface::startReceive() int err = lora.startReceive(RADIOLIB_SX128X_RX_TIMEOUT_INF, RADIOLIB_IRQ_RX_DEFAULT_FLAGS | RADIOLIB_IRQ_PREAMBLE_DETECTED); if (err != RADIOLIB_ERR_NONE) - LOG_ERROR("Radiolib error %d when attempting SX128X startReceive!\n", err); + LOG_ERROR("SX128X startReceive %s%d\n", radioLibErr, err); assert(err == RADIOLIB_ERR_NONE); RadioLibInterface::startReceive(); @@ -282,7 +282,7 @@ template bool SX128xInterface::isChannelActive() if (result == RADIOLIB_LORA_DETECTED) return true; if (result != RADIOLIB_CHANNEL_FREE) - LOG_ERROR("Radiolib error %d when attempting SX128X scanChannel!\n", result); + LOG_ERROR("SX128X scanChannel %s%d\n", radioLibErr, result); assert(result != RADIOLIB_ERR_WRONG_MODEM); return false; @@ -298,8 +298,8 @@ template bool SX128xInterface::sleep() { // Not keeping config is busted - next time nrf52 board boots lora sending fails tcxo related? - see datasheet // \todo Display actual typename of the adapter, not just `SX128x` - LOG_DEBUG("SX128x entering sleep mode (FIXME, don't keep config)\n"); - setStandby(); // Stop any pending operations + LOG_DEBUG("SX128x entering sleep mode\n"); // (FIXME, don't keep config) + setStandby(); // Stop any pending operations // turn off TCXO if it was powered // FIXME - this isn't correct diff --git a/src/mesh/http/ContentHandler.cpp b/src/mesh/http/ContentHandler.cpp index 772b3e821..c5ea86429 100644 --- a/src/mesh/http/ContentHandler.cpp +++ b/src/mesh/http/ContentHandler.cpp @@ -776,7 +776,7 @@ void handleRestart(HTTPRequest *req, HTTPResponse *res) res->println("

Meshtastic

\n"); res->println("Restarting"); - LOG_DEBUG("***** Restarted on HTTP(s) Request *****\n"); + LOG_DEBUG("Restarted on HTTP(s) Request\n"); webServerThread->requestRestart = (millis() / 1000) + 5; } diff --git a/src/modules/StoreForwardModule.cpp b/src/modules/StoreForwardModule.cpp index 5f30803a4..58be8c01e 100644 --- a/src/modules/StoreForwardModule.cpp +++ b/src/modules/StoreForwardModule.cpp @@ -46,7 +46,7 @@ int32_t StoreForwardModule::runOnce() } else if (this->heartbeat && (!Throttle::isWithinTimespanMs(lastHeartbeat, heartbeatInterval * 1000)) && airTime->isTxAllowedChannelUtil(true)) { lastHeartbeat = millis(); - LOG_INFO("*** Sending heartbeat\n"); + LOG_INFO("Sending heartbeat\n"); meshtastic_StoreAndForward sf = meshtastic_StoreAndForward_init_zero; sf.rr = meshtastic_StoreAndForward_RequestResponse_ROUTER_HEARTBEAT; sf.which_variant = meshtastic_StoreAndForward_heartbeat_tag; @@ -70,8 +70,8 @@ void StoreForwardModule::populatePSRAM() https://learn.upesy.com/en/programmation/psram.html#psram-tab */ - LOG_DEBUG("*** Before PSRAM initialization: heap %d/%d PSRAM %d/%d\n", memGet.getFreeHeap(), memGet.getHeapSize(), - memGet.getFreePsram(), memGet.getPsramSize()); + LOG_DEBUG("Before PSRAM init: heap %d/%d PSRAM %d/%d\n", memGet.getFreeHeap(), memGet.getHeapSize(), memGet.getFreePsram(), + memGet.getPsramSize()); /* Use a maximum of 2/3 the available PSRAM unless otherwise specified. Note: This needs to be done after every thing that would use PSRAM @@ -86,9 +86,9 @@ void StoreForwardModule::populatePSRAM() #endif - LOG_DEBUG("*** After PSRAM initialization: heap %d/%d PSRAM %d/%d\n", memGet.getFreeHeap(), memGet.getHeapSize(), - memGet.getFreePsram(), memGet.getPsramSize()); - LOG_DEBUG("*** numberOfPackets for packetHistory - %u\n", numberOfPackets); + LOG_DEBUG("After PSRAM init: heap %d/%d PSRAM %d/%d\n", memGet.getFreeHeap(), memGet.getHeapSize(), memGet.getFreePsram(), + memGet.getPsramSize()); + LOG_DEBUG("numberOfPackets for packetHistory - %u\n", numberOfPackets); } /** @@ -105,11 +105,11 @@ void StoreForwardModule::historySend(uint32_t secAgo, uint32_t to) queueSize = this->historyReturnMax; if (queueSize) { - LOG_INFO("*** S&F - Sending %u message(s)\n", queueSize); + LOG_INFO("S&F - Sending %u message(s)\n", queueSize); this->busy = true; // runOnce() will pickup the next steps once busy = true. this->busyTo = to; } else { - LOG_INFO("*** S&F - No history to send\n"); + LOG_INFO("S&F - No history\n"); } meshtastic_StoreAndForward sf = meshtastic_StoreAndForward_init_zero; sf.rr = meshtastic_StoreAndForward_RequestResponse_ROUTER_HISTORY; @@ -187,7 +187,7 @@ void StoreForwardModule::historyAdd(const meshtastic_MeshPacket &mp) const auto &p = mp.decoded; if (this->packetHistoryTotalCount == this->records) { - LOG_WARN("*** S&F - PSRAM Full. Starting overwrite now.\n"); + LOG_WARN("S&F - PSRAM Full. Starting overwrite.\n"); this->packetHistoryTotalCount = 0; for (auto &i : lastRequest) { i.second = 0; // Clear the last request index for each client device @@ -215,7 +215,7 @@ bool StoreForwardModule::sendPayload(NodeNum dest, uint32_t last_time) { meshtastic_MeshPacket *p = preparePayload(dest, last_time); if (p) { - LOG_INFO("*** Sending S&F Payload\n"); + LOG_INFO("Sending S&F Payload\n"); service->sendToMesh(p); this->requestCount++; return true; @@ -331,9 +331,9 @@ void StoreForwardModule::sendErrorTextMessage(NodeNum dest, bool want_response) pr->decoded.portnum = meshtastic_PortNum_TEXT_MESSAGE_APP; const char *str; if (this->busy) { - str = "** S&F - Busy. Try again shortly."; + str = "S&F - Busy. Try again shortly."; } else { - str = "** S&F - Not available on this channel."; + str = "S&F - Not available on this channel."; } LOG_WARN("%s\n", str); memcpy(pr->decoded.payload.bytes, str, strlen(str)); @@ -365,7 +365,7 @@ void StoreForwardModule::statsSend(uint32_t to) sf.variant.stats.return_max = this->historyReturnMax; sf.variant.stats.return_window = this->historyReturnWindow; - LOG_DEBUG("*** Sending S&F Stats\n"); + LOG_DEBUG("Sending S&F Stats\n"); storeForwardModule->sendMessage(to, sf); } @@ -384,7 +384,7 @@ ProcessMessage StoreForwardModule::handleReceived(const meshtastic_MeshPacket &m auto &p = mp.decoded; if (mp.to == nodeDB->getNodeNum() && (p.payload.bytes[0] == 'S') && (p.payload.bytes[1] == 'F') && (p.payload.bytes[2] == 0x00)) { - LOG_DEBUG("*** Legacy Request to send\n"); + LOG_DEBUG("Legacy Request to send\n"); // Send the last 60 minutes of messages. if (this->busy || channels.isDefaultChannel(mp.channel)) { @@ -394,7 +394,7 @@ ProcessMessage StoreForwardModule::handleReceived(const meshtastic_MeshPacket &m } } else { storeForwardModule->historyAdd(mp); - LOG_INFO("*** S&F stored. Message history contains %u records now.\n", this->packetHistoryTotalCount); + LOG_INFO("S&F stored. Message history contains %u records now.\n", this->packetHistoryTotalCount); } } else if (getFrom(&mp) != nodeDB->getNodeNum() && mp.decoded.portnum == meshtastic_PortNum_STORE_FORWARD_APP) { auto &p = mp.decoded; @@ -440,7 +440,7 @@ bool StoreForwardModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, if (is_server) { // stop sending stuff, the client wants to abort or has another error if ((this->busy) && (this->busyTo == getFrom(&mp))) { - LOG_ERROR("*** Client in ERROR or ABORT requested\n"); + LOG_ERROR("Client in ERROR or ABORT requested\n"); this->requestCount = 0; this->busy = false; } @@ -450,7 +450,7 @@ bool StoreForwardModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, case meshtastic_StoreAndForward_RequestResponse_CLIENT_HISTORY: if (is_server) { requests_history++; - LOG_INFO("*** Client Request to send HISTORY\n"); + LOG_INFO("Client Request to send HISTORY\n"); // Send the last 60 minutes of messages. if (this->busy || channels.isDefaultChannel(mp.channel)) { sendErrorTextMessage(getFrom(&mp), mp.decoded.want_response); @@ -467,7 +467,6 @@ bool StoreForwardModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, case meshtastic_StoreAndForward_RequestResponse_CLIENT_PING: if (is_server) { - LOG_INFO("*** StoreAndForward_RequestResponse_CLIENT_PING\n"); // respond with a ROUTER PONG storeForwardModule->sendMessage(getFrom(&mp), meshtastic_StoreAndForward_RequestResponse_ROUTER_PONG); } @@ -475,17 +474,16 @@ bool StoreForwardModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, case meshtastic_StoreAndForward_RequestResponse_CLIENT_PONG: if (is_server) { - LOG_INFO("*** StoreAndForward_RequestResponse_CLIENT_PONG\n"); // NodeDB is already updated } break; case meshtastic_StoreAndForward_RequestResponse_CLIENT_STATS: if (is_server) { - LOG_INFO("*** Client Request to send STATS\n"); + LOG_INFO("Client Request to send STATS\n"); if (this->busy) { storeForwardModule->sendMessage(getFrom(&mp), meshtastic_StoreAndForward_RequestResponse_ROUTER_BUSY); - LOG_INFO("*** S&F - Busy. Try again shortly.\n"); + LOG_INFO("S&F - Busy. Try again shortly.\n"); } else { storeForwardModule->statsSend(getFrom(&mp)); } @@ -495,7 +493,7 @@ bool StoreForwardModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, case meshtastic_StoreAndForward_RequestResponse_ROUTER_ERROR: case meshtastic_StoreAndForward_RequestResponse_ROUTER_BUSY: if (is_client) { - LOG_DEBUG("*** StoreAndForward_RequestResponse_ROUTER_BUSY\n"); + LOG_DEBUG("StoreAndForward_RequestResponse_ROUTER_BUSY\n"); // retry in messages_saved * packetTimeMax ms retry_delay = millis() + getNumAvailablePackets(this->busyTo, this->last_time) * packetTimeMax * (meshtastic_StoreAndForward_RequestResponse_ROUTER_ERROR ? 2 : 1); @@ -511,13 +509,12 @@ bool StoreForwardModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, heartbeatInterval = p->variant.heartbeat.period; } lastHeartbeat = millis(); - LOG_INFO("*** StoreAndForward Heartbeat received\n"); + LOG_INFO("StoreAndForward Heartbeat received\n"); } break; case meshtastic_StoreAndForward_RequestResponse_ROUTER_PING: if (is_client) { - LOG_DEBUG("*** StoreAndForward_RequestResponse_ROUTER_PING\n"); // respond with a CLIENT PONG storeForwardModule->sendMessage(getFrom(&mp), meshtastic_StoreAndForward_RequestResponse_CLIENT_PONG); } @@ -525,7 +522,7 @@ bool StoreForwardModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, case meshtastic_StoreAndForward_RequestResponse_ROUTER_STATS: if (is_client) { - LOG_DEBUG("*** Router Response STATS\n"); + LOG_DEBUG("Router Response STATS\n"); // These fields only have informational purpose on a client. Fill them to consume later. if (p->which_variant == meshtastic_StoreAndForward_stats_tag) { this->records = p->variant.stats.messages_max; @@ -543,7 +540,7 @@ bool StoreForwardModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, // These fields only have informational purpose on a client. Fill them to consume later. if (p->which_variant == meshtastic_StoreAndForward_history_tag) { this->historyReturnWindow = p->variant.history.window / 60000; - LOG_INFO("*** Router Response HISTORY - Sending %d messages from last %d minutes\n", + LOG_INFO("Router Response HISTORY - Sending %d messages from last %d minutes\n", p->variant.history.history_messages, this->historyReturnWindow); } } @@ -577,7 +574,7 @@ StoreForwardModule::StoreForwardModule() // Router if ((config.device.role == meshtastic_Config_DeviceConfig_Role_ROUTER || moduleConfig.store_forward.is_server)) { - LOG_INFO("*** Initializing Store & Forward Module in Server mode\n"); + LOG_INFO("Initializing Store & Forward Module in Server mode\n"); if (memGet.getPsramSize() > 0) { if (memGet.getFreePsram() >= 1024 * 1024) { @@ -605,18 +602,17 @@ StoreForwardModule::StoreForwardModule() this->populatePSRAM(); is_server = true; } else { - LOG_INFO("*** Device has less than 1M of PSRAM free.\n"); - LOG_INFO("*** Store & Forward Module - disabling server.\n"); + LOG_INFO(".\n"); + LOG_INFO("S&F: not enough PSRAM free, disabling.\n"); } } else { - LOG_INFO("*** Device doesn't have PSRAM.\n"); - LOG_INFO("*** Store & Forward Module - disabling server.\n"); + LOG_INFO("S&F: device doesn't have PSRAM, disabling.\n"); } // Client } else { is_client = true; - LOG_INFO("*** Initializing Store & Forward Module in Client mode\n"); + LOG_INFO("Initializing Store & Forward Module in Client mode\n"); } } else { disable(); diff --git a/src/modules/Telemetry/PowerTelemetry.cpp b/src/modules/Telemetry/PowerTelemetry.cpp index d31892042..038cbfadc 100644 --- a/src/modules/Telemetry/PowerTelemetry.cpp +++ b/src/modules/Telemetry/PowerTelemetry.cpp @@ -255,7 +255,7 @@ bool PowerTelemetryModule::sendTelemetry(NodeNum dest, bool phoneOnly) service->sendToMesh(p, RX_SRC_LOCAL, true); if (config.device.role == meshtastic_Config_DeviceConfig_Role_SENSOR && config.power.is_power_saving) { - LOG_DEBUG("Starting next execution in 5 seconds and then going to sleep.\n"); + LOG_DEBUG("Starting next execution in 5s then going to sleep.\n"); sleepOnNextExecution = true; setIntervalFromNow(5000); } diff --git a/src/modules/Telemetry/Sensor/MAX17048Sensor.cpp b/src/modules/Telemetry/Sensor/MAX17048Sensor.cpp index a3890df43..96dd5ae80 100644 --- a/src/modules/Telemetry/Sensor/MAX17048Sensor.cpp +++ b/src/modules/Telemetry/Sensor/MAX17048Sensor.cpp @@ -19,7 +19,7 @@ MAX17048Singleton *MAX17048Singleton::pinstance{nullptr}; bool MAX17048Singleton::runOnce(TwoWire *theWire) { initialized = begin(theWire); - LOG_DEBUG("MAX17048Sensor::runOnce %s\n", initialized ? "began ok" : "begin failed"); + LOG_DEBUG("%s::runOnce %s\n", sensorStr, initialized ? "began ok" : "begin failed"); return initialized; } @@ -27,7 +27,7 @@ bool MAX17048Singleton::isBatteryCharging() { float volts = cellVoltage(); if (isnan(volts)) { - LOG_DEBUG("MAX17048Sensor::isBatteryCharging is not connected\n"); + LOG_DEBUG("%s::isBatteryCharging is not connected\n", sensorStr); return 0; } @@ -53,7 +53,7 @@ bool MAX17048Singleton::isBatteryCharging() chargeState = MAX17048ChargeState::IDLE; } - LOG_DEBUG("MAX17048Sensor::isBatteryCharging %s volts: %.3f soc: %.3f rate: %.3f\n", chargeLabels[chargeState], volts, + LOG_DEBUG("%s::isBatteryCharging %s volts: %.3f soc: %.3f rate: %.3f\n", sensorStr, chargeLabels[chargeState], volts, sample.cellPercent, sample.chargeRate); return chargeState == MAX17048ChargeState::IMPORT; } @@ -62,17 +62,17 @@ uint16_t MAX17048Singleton::getBusVoltageMv() { float volts = cellVoltage(); if (isnan(volts)) { - LOG_DEBUG("MAX17048Sensor::getBusVoltageMv is not connected\n"); + LOG_DEBUG("%s::getBusVoltageMv is not connected\n", sensorStr); return 0; } - LOG_DEBUG("MAX17048Sensor::getBusVoltageMv %.3fmV\n", volts); + LOG_DEBUG("%s::getBusVoltageMv %.3fmV\n", sensorStr, volts); return (uint16_t)(volts * 1000.0f); } uint8_t MAX17048Singleton::getBusBatteryPercent() { float soc = cellPercent(); - LOG_DEBUG("MAX17048Sensor::getBusBatteryPercent %.1f%%\n", soc); + LOG_DEBUG("%s::getBusBatteryPercent %.1f%%\n", sensorStr, soc); return clamp(static_cast(round(soc)), static_cast(0), static_cast(100)); } @@ -82,7 +82,7 @@ uint16_t MAX17048Singleton::getTimeToGoSecs() float soc = cellPercent(); // state of charge in percent 0 to 100 soc = clamp(soc, 0.0f, 100.0f); // clamp soc between 0 and 100% float ttg = ((100.0f - soc) / rate) * 3600.0f; // calculate seconds to charge/discharge - LOG_DEBUG("MAX17048Sensor::getTimeToGoSecs %.0f seconds\n", ttg); + LOG_DEBUG("%s::getTimeToGoSecs %.0f seconds\n", sensorStr, ttg); return (uint16_t)ttg; } @@ -90,7 +90,7 @@ bool MAX17048Singleton::isBatteryConnected() { float volts = cellVoltage(); if (isnan(volts)) { - LOG_DEBUG("MAX17048Sensor::isBatteryConnected is not connected\n"); + LOG_DEBUG("%s::isBatteryConnected is not connected\n", sensorStr); return false; } @@ -103,12 +103,12 @@ bool MAX17048Singleton::isExternallyPowered() float volts = cellVoltage(); if (isnan(volts)) { // if the battery is not connected then there must be external power - LOG_DEBUG("MAX17048Sensor::isExternallyPowered battery is\n"); + LOG_DEBUG("%s::isExternallyPowered battery is\n", sensorStr); return true; } // if the bus voltage is over MAX17048_BUS_POWER_VOLTS, then the external power // is assumed to be connected - LOG_DEBUG("MAX17048Sensor::isExternallyPowered %s connected\n", volts >= MAX17048_BUS_POWER_VOLTS ? "is" : "is not"); + LOG_DEBUG("%s::isExternallyPowered %s connected\n", sensorStr, volts >= MAX17048_BUS_POWER_VOLTS ? "is" : "is not"); return volts >= MAX17048_BUS_POWER_VOLTS; } diff --git a/src/modules/Telemetry/Sensor/MAX17048Sensor.h b/src/modules/Telemetry/Sensor/MAX17048Sensor.h index 20dca324c..bd109cbb1 100644 --- a/src/modules/Telemetry/Sensor/MAX17048Sensor.h +++ b/src/modules/Telemetry/Sensor/MAX17048Sensor.h @@ -40,6 +40,7 @@ class MAX17048Singleton : public Adafruit_MAX17048 std::queue chargeSamples; MAX17048ChargeState chargeState = IDLE; const String chargeLabels[3] = {F("idle"), F("export"), F("import")}; + const char *sensorStr = "MAX17048Sensor"; protected: MAX17048Singleton(); diff --git a/src/modules/TraceRouteModule.cpp b/src/modules/TraceRouteModule.cpp index 1f652dbf6..be8278824 100644 --- a/src/modules/TraceRouteModule.cpp +++ b/src/modules/TraceRouteModule.cpp @@ -101,7 +101,7 @@ void TraceRouteModule::appendMyIDandSNR(meshtastic_RouteDiscovery *updated, floa route[*route_count] = myNodeInfo.my_node_num; *route_count += 1; } else { - LOG_WARN("Route exceeded maximum hop limit, are you bridging networks?\n"); + LOG_WARN("Route exceeded maximum hop limit!\n"); // Are you bridging networks? } } diff --git a/src/serialization/MeshPacketSerializer.cpp b/src/serialization/MeshPacketSerializer.cpp index e00dde024..acda94fac 100644 --- a/src/serialization/MeshPacketSerializer.cpp +++ b/src/serialization/MeshPacketSerializer.cpp @@ -93,7 +93,7 @@ std::string MeshPacketSerializer::JsonSerialize(const meshtastic_MeshPacket *mp, } jsonObj["payload"] = new JSONValue(msgPayload); } else if (shouldLog) { - LOG_ERROR("Error decoding protobuf for telemetry message!\n"); + LOG_ERROR(errStr, msgType.c_str()); } break; } @@ -111,7 +111,7 @@ std::string MeshPacketSerializer::JsonSerialize(const meshtastic_MeshPacket *mp, msgPayload["role"] = new JSONValue((int)decoded->role); jsonObj["payload"] = new JSONValue(msgPayload); } else if (shouldLog) { - LOG_ERROR("Error decoding protobuf for nodeinfo message!\n"); + LOG_ERROR(errStr, msgType.c_str()); } break; } @@ -156,12 +156,12 @@ std::string MeshPacketSerializer::JsonSerialize(const meshtastic_MeshPacket *mp, } jsonObj["payload"] = new JSONValue(msgPayload); } else if (shouldLog) { - LOG_ERROR("Error decoding protobuf for position message!\n"); + LOG_ERROR(errStr, msgType.c_str()); } break; } case meshtastic_PortNum_WAYPOINT_APP: { - msgType = "position"; + msgType = "waypoint"; meshtastic_Waypoint scratch; meshtastic_Waypoint *decoded = NULL; memset(&scratch, 0, sizeof(scratch)); @@ -176,7 +176,7 @@ std::string MeshPacketSerializer::JsonSerialize(const meshtastic_MeshPacket *mp, msgPayload["longitude_i"] = new JSONValue((int)decoded->longitude_i); jsonObj["payload"] = new JSONValue(msgPayload); } else if (shouldLog) { - LOG_ERROR("Error decoding protobuf for position message!\n"); + LOG_ERROR(errStr, msgType.c_str()); } break; } @@ -202,7 +202,7 @@ std::string MeshPacketSerializer::JsonSerialize(const meshtastic_MeshPacket *mp, msgPayload["neighbors"] = new JSONValue(neighbors); jsonObj["payload"] = new JSONValue(msgPayload); } else if (shouldLog) { - LOG_ERROR("Error decoding protobuf for neighborinfo message!\n"); + LOG_ERROR(errStr, msgType.c_str()); } break; } @@ -234,7 +234,7 @@ std::string MeshPacketSerializer::JsonSerialize(const meshtastic_MeshPacket *mp, msgPayload["route"] = new JSONValue(route); jsonObj["payload"] = new JSONValue(msgPayload); } else if (shouldLog) { - LOG_ERROR("Error decoding protobuf for traceroute message!\n"); + LOG_ERROR(errStr, msgType.c_str()); } } break; @@ -261,7 +261,7 @@ std::string MeshPacketSerializer::JsonSerialize(const meshtastic_MeshPacket *mp, msgPayload["uptime"] = new JSONValue((unsigned int)decoded->uptime); jsonObj["payload"] = new JSONValue(msgPayload); } else if (shouldLog) { - LOG_ERROR("Error decoding protobuf for Paxcount message!\n"); + LOG_ERROR(errStr, msgType.c_str()); } break; } @@ -284,7 +284,7 @@ std::string MeshPacketSerializer::JsonSerialize(const meshtastic_MeshPacket *mp, jsonObj["payload"] = new JSONValue(msgPayload); } } else if (shouldLog) { - LOG_ERROR("Error decoding protobuf for RemoteHardware message!\n"); + LOG_ERROR(errStr, "RemoteHardware"); } break; } diff --git a/src/serialization/MeshPacketSerializer.h b/src/serialization/MeshPacketSerializer.h index 03860ab35..989f30fc0 100644 --- a/src/serialization/MeshPacketSerializer.h +++ b/src/serialization/MeshPacketSerializer.h @@ -2,6 +2,7 @@ #include static const char hexChars[16] = {'0', '1', '2', '3', '4', '5', '6', '7', '8', '9', 'A', 'B', 'C', 'D', 'E', 'F'}; +static const char *errStr = "Error decoding protobuf for %s message!\n"; class MeshPacketSerializer { From b8044c498309be68f10e01d79d4e66d38d31eba1 Mon Sep 17 00:00:00 2001 From: todd-herbert Date: Wed, 2 Oct 2024 23:37:08 +1300 Subject: [PATCH 43/88] Tweak dimensions for Canned Message Notifications (#4924) --- src/modules/CannedMessageModule.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/CannedMessageModule.cpp b/src/modules/CannedMessageModule.cpp index e38b7e063..615a1ab54 100644 --- a/src/modules/CannedMessageModule.cpp +++ b/src/modules/CannedMessageModule.cpp @@ -998,7 +998,7 @@ void CannedMessageModule::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *st int16_t rssiY = 130; // If dislay is *slighly* too small for the original consants, squish up a bit - if (display->getHeight() < rssiY) { + if (display->getHeight() < rssiY + FONT_HEIGHT_SMALL) { snrY = display->getHeight() - ((1.5) * FONT_HEIGHT_SMALL); rssiY = display->getHeight() - ((2.5) * FONT_HEIGHT_SMALL); } From 00f15459eceee4b63fce0b86371fa37e1e5e8a75 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Wed, 2 Oct 2024 06:14:24 -0500 Subject: [PATCH 44/88] Userprefs prefix macros for clarity and consistency (#4923) * Convert userprefs macros to prefixed ones for clarity * Fix key --- src/graphics/Screen.cpp | 4 ++-- src/graphics/img/icon.xbm | 2 +- src/mesh/Channels.cpp | 22 +++++++++++----------- src/mesh/Default.cpp | 2 +- src/mesh/FloodingRouter.cpp | 2 +- src/mesh/NodeDB.cpp | 24 ++++++++++++------------ src/mesh/Router.cpp | 2 +- src/modules/AdminModule.cpp | 2 +- userPrefs.h | 28 ++++++++++++++-------------- 9 files changed, 44 insertions(+), 44 deletions(-) diff --git a/src/graphics/Screen.cpp b/src/graphics/Screen.cpp index ef6b05ca4..50350a310 100644 --- a/src/graphics/Screen.cpp +++ b/src/graphics/Screen.cpp @@ -163,8 +163,8 @@ static void drawIconScreen(const char *upperMsg, OLEDDisplay *display, OLEDDispl display->setFont(FONT_MEDIUM); display->setTextAlignment(TEXT_ALIGN_LEFT); -#ifdef SPLASH_TITLE_USERPREFS - const char *title = SPLASH_TITLE_USERPREFS; +#ifdef USERPREFS_SPLASH_TITLE + const char *title = USERPREFS_SPLASH_TITLE; #else const char *title = "meshtastic.org"; #endif diff --git a/src/graphics/img/icon.xbm b/src/graphics/img/icon.xbm index f90cf4946..4e78ae8a1 100644 --- a/src/graphics/img/icon.xbm +++ b/src/graphics/img/icon.xbm @@ -1,4 +1,4 @@ -#ifndef HAS_USERPREFS_SPLASH +#ifndef USERPREFS_HAS_SPLASH #define icon_width 50 #define icon_height 28 static uint8_t icon_bits[] = { diff --git a/src/mesh/Channels.cpp b/src/mesh/Channels.cpp index 47c013443..c8ac09a37 100644 --- a/src/mesh/Channels.cpp +++ b/src/mesh/Channels.cpp @@ -99,26 +99,26 @@ void Channels::initDefaultChannel(ChannelIndex chIndex) ch.has_settings = true; ch.role = meshtastic_Channel_Role_PRIMARY; -#ifdef LORACONFIG_MODEM_PRESET_USERPREFS - loraConfig.modem_preset = LORACONFIG_MODEM_PRESET_USERPREFS; +#ifdef USERPREFS_LORACONFIG_MODEM_PRESET + loraConfig.modem_preset = USERPREFS_LORACONFIG_MODEM_PRESET; #endif -#ifdef LORACONFIG_CHANNEL_NUM_USERPREFS - loraConfig.channel_num = LORACONFIG_CHANNEL_NUM_USERPREFS; +#ifdef USERPREFS_LORACONFIG_CHANNEL_NUM + loraConfig.channel_num = USERPREFS_LORACONFIG_CHANNEL_NUM; #endif // Install custom defaults. Will eventually support setting multiple default channels if (chIndex == 0) { -#ifdef CHANNEL_0_PSK_USERPREFS - static const uint8_t defaultpsk[] = CHANNEL_0_PSK_USERPREFS; +#ifdef USERPREFS_CHANNEL_0_PSK + static const uint8_t defaultpsk[] = USERPREFS_CHANNEL_0_PSK; memcpy(channelSettings.psk.bytes, defaultpsk, sizeof(defaultpsk)); channelSettings.psk.size = sizeof(defaultpsk); #endif -#ifdef CHANNEL_0_NAME_USERPREFS - strcpy(channelSettings.name, CHANNEL_0_NAME_USERPREFS); +#ifdef USERPREFS_CHANNEL_0_NAME + strcpy(channelSettings.name, USERPREFS_CHANNEL_0_NAME); #endif -#ifdef CHANNEL_0_PRECISION_USERPREFS - channelSettings.module_settings.position_precision = CHANNEL_0_PRECISION_USERPREFS; +#ifdef USERPREFS_CHANNEL_0_PRECISION + channelSettings.module_settings.position_precision = USERPREFS_CHANNEL_0_PRECISION; #endif } } @@ -273,7 +273,7 @@ void Channels::setChannel(const meshtastic_Channel &c) bool Channels::anyMqttEnabled() { -#if EVENT_MODE +#if USERPREFS_EVENT_MODE // Don't publish messages on the public MQTT broker if we are in event mode if (strcmp(moduleConfig.mqtt.address, default_mqtt_address) == 0) { return false; diff --git a/src/mesh/Default.cpp b/src/mesh/Default.cpp index ac7441394..0bedcfc91 100644 --- a/src/mesh/Default.cpp +++ b/src/mesh/Default.cpp @@ -45,7 +45,7 @@ uint32_t Default::getConfiguredOrDefaultMsScaled(uint32_t configured, uint32_t d uint8_t Default::getConfiguredOrDefaultHopLimit(uint8_t configured) { -#if EVENT_MODE +#if USERPREFS_EVENT_MODE return (configured > HOP_RELIABLE) ? HOP_RELIABLE : config.lora.hop_limit; #else return (configured >= HOP_MAX) ? HOP_MAX : config.lora.hop_limit; diff --git a/src/mesh/FloodingRouter.cpp b/src/mesh/FloodingRouter.cpp index e2dbd8997..037fdd2ae 100644 --- a/src/mesh/FloodingRouter.cpp +++ b/src/mesh/FloodingRouter.cpp @@ -47,7 +47,7 @@ void FloodingRouter::sniffReceived(const meshtastic_MeshPacket *p, const meshtas meshtastic_MeshPacket *tosend = packetPool.allocCopy(*p); // keep a copy because we will be sending it tosend->hop_limit--; // bump down the hop count -#if EVENT_MODE +#if USERPREFS_EVENT_MODE if (tosend->hop_limit > 2) { // if we are "correcting" the hop_limit, "correct" the hop_start by the same amount to preserve hops away. tosend->hop_start -= (tosend->hop_limit - 2); diff --git a/src/mesh/NodeDB.cpp b/src/mesh/NodeDB.cpp index b78827e65..25314a086 100644 --- a/src/mesh/NodeDB.cpp +++ b/src/mesh/NodeDB.cpp @@ -286,24 +286,24 @@ void NodeDB::installDefaultConfig(bool preserveKey = false) true; // FIXME: maybe false in the future, and setting region to enable it. (unset region forces it off) config.lora.override_duty_cycle = false; config.lora.config_ok_to_mqtt = false; -#ifdef CONFIG_LORA_REGION_USERPREFS - config.lora.region = CONFIG_LORA_REGION_USERPREFS; +#ifdef USERPREFS_CONFIG_LORA_REGION + config.lora.region = USERPREFS_CONFIG_LORA_REGION; #else config.lora.region = meshtastic_Config_LoRaConfig_RegionCode_UNSET; #endif -#ifdef LORACONFIG_MODEM_PRESET_USERPREFS - config.lora.modem_preset = LORACONFIG_MODEM_PRESET_USERPREFS; +#ifdef USERPREFS_LORACONFIG_MODEM_PRESET + config.lora.modem_preset = USERPREFS_LORACONFIG_MODEM_PRESET; #else config.lora.modem_preset = meshtastic_Config_LoRaConfig_ModemPreset_LONG_FAST; #endif config.lora.hop_limit = HOP_RELIABLE; -#ifdef CONFIG_LORA_IGNORE_MQTT_USERPREFS - config.lora.ignore_mqtt = CONFIG_LORA_IGNORE_MQTT_USERPREFS; +#ifdef USERPREFS_CONFIG_LORA_IGNORE_MQTT + config.lora.ignore_mqtt = USERPREFS_CONFIG_LORA_IGNORE_MQTT; #else config.lora.ignore_mqtt = false; #endif -#ifdef ADMIN_KEY_USERPREFS - memcpy(config.security.admin_key[0].bytes, admin_key_userprefs, 32); +#ifdef USERPREFS_USE_ADMIN_KEY + memcpy(config.security.admin_key[0].bytes, USERPREFS_ADMIN_KEY, 32); config.security.admin_key[0].size = 32; #else config.security.admin_key[0].size = 0; @@ -617,13 +617,13 @@ void NodeDB::installDefaultDeviceState() // Set default owner name pickNewNodeNum(); // based on macaddr now -#ifdef CONFIG_OWNER_LONG_NAME_USERPREFS - snprintf(owner.long_name, sizeof(owner.long_name), CONFIG_OWNER_LONG_NAME_USERPREFS); +#ifdef USERPREFS_CONFIG_OWNER_LONG_NAME + snprintf(owner.long_name, sizeof(owner.long_name), USERPREFS_CONFIG_OWNER_LONG_NAME); #else snprintf(owner.long_name, sizeof(owner.long_name), "Meshtastic %02x%02x", ourMacAddr[4], ourMacAddr[5]); #endif -#ifdef CONFIG_OWNER_SHORT_NAME_USERPREFS - snprintf(owner.short_name, sizeof(owner.short_name), CONFIG_OWNER_SHORT_NAME_USERPREFS); +#ifdef USERPREFS_CONFIG_OWNER_SHORT_NAME + snprintf(owner.short_name, sizeof(owner.short_name), USERPREFS_CONFIG_OWNER_SHORT_NAME); #else snprintf(owner.short_name, sizeof(owner.short_name), "%02x%02x", ourMacAddr[4], ourMacAddr[5]); #endif diff --git a/src/mesh/Router.cpp b/src/mesh/Router.cpp index 610d5303e..6ff4364d1 100644 --- a/src/mesh/Router.cpp +++ b/src/mesh/Router.cpp @@ -590,7 +590,7 @@ void Router::handleReceived(meshtastic_MeshPacket *p, RxSource src) skipHandle = true; } -#if EVENT_MODE +#if USERPREFS_EVENT_MODE if (p->which_payload_variant == meshtastic_MeshPacket_decoded_tag && (p->decoded.portnum == meshtastic_PortNum_ATAK_FORWARDER || p->decoded.portnum == meshtastic_PortNum_ATAK_PLUGIN || p->decoded.portnum == meshtastic_PortNum_PAXCOUNTER_APP || p->decoded.portnum == meshtastic_PortNum_IP_TUNNEL_APP || diff --git a/src/modules/AdminModule.cpp b/src/modules/AdminModule.cpp index 4a7af4817..b94bbddf2 100644 --- a/src/modules/AdminModule.cpp +++ b/src/modules/AdminModule.cpp @@ -467,7 +467,7 @@ void AdminModule::handleSetConfig(const meshtastic_Config &c) requiresReboot = true; } } -#if EVENT_MODE +#if USERPREFS_EVENT_MODE // If we're in event mode, nobody is a Router or Repeater if (config.device.role == meshtastic_Config_DeviceConfig_Role_ROUTER || config.device.role == meshtastic_Config_DeviceConfig_Role_REPEATER) { diff --git a/userPrefs.h b/userPrefs.h index 3b32bf79b..40f2cc6d2 100644 --- a/userPrefs.h +++ b/userPrefs.h @@ -3,29 +3,29 @@ // Uncomment and modify to set device defaults -// #define EVENT_MODE 1 +// #define USERPREFS_EVENT_MODE 1 -// #define CONFIG_LORA_REGION_USERPREFS meshtastic_Config_LoRaConfig_RegionCode_US -// #define LORACONFIG_MODEM_PRESET_USERPREFS meshtastic_Config_LoRaConfig_ModemPreset_SHORT_FAST -// #define LORACONFIG_CHANNEL_NUM_USERPREFS 31 -// #define CONFIG_LORA_IGNORE_MQTT_USERPREFS true +// #define USERPREFS_CONFIG_LORA_REGION meshtastic_Config_LoRaConfig_RegionCode_US +// #define USERPREFS_LORACONFIG_MODEM_PRESET meshtastic_Config_LoRaConfig_ModemPreset_SHORT_FAST +// #define USERPREFS_LORACONFIG_CHANNEL_NUM 31 +// #define USERPREFS_CONFIG_LORA_IGNORE_MQTT true /* -#define CHANNEL_0_PSK_USERPREFS \ +#define USERPREFS_CHANNEL_0_PSK \ { \ 0x38, 0x4b, 0xbc, 0xc0, 0x1d, 0xc0, 0x22, 0xd1, 0x81, 0xbf, 0x36, 0xb8, 0x61, 0x21, 0xe1, 0xfb, 0x96, 0xb7, 0x2e, 0x55, \ 0xbf, 0x74, 0x22, 0x7e, 0x9d, 0x6a, 0xfb, 0x48, 0xd6, 0x4c, 0xb1, 0xa1 \ } */ -// #define CHANNEL_0_NAME_USERPREFS "DEFCONnect" -// #define CHANNEL_0_PRECISION_USERPREFS 14 +// #define USERPREFS_CHANNEL_0_NAME "DEFCONnect" +// #define USERPREFS_CHANNEL_0_PRECISION 14 -// #define CONFIG_OWNER_LONG_NAME_USERPREFS "My Long Name" -// #define CONFIG_OWNER_SHORT_NAME_USERPREFS "MLN" +// #define USERPREFS_CONFIG_OWNER_LONG_NAME "My Long Name" +// #define USERPREFS_CONFIG_OWNER_SHORT_NAME "MLN" -// #define SPLASH_TITLE_USERPREFS "DEFCONtastic" +// #define USERPREFS_SPLASH_TITLE "DEFCONtastic" // #define icon_width 34 // #define icon_height 29 -// #define HAS_USERPREFS_SPLASH +// #define USERPREFS_HAS_SPLASH /* static unsigned char icon_bits[] = { 0x00, 0xC0, 0x0F, 0x00, 0x00, 0x00, 0xF0, 0x3F, 0x00, 0x00, 0x00, 0xF8, 0x7F, 0x00, 0x00, 0x00, 0xFC, 0xFF, 0x00, 0x00, 0x00, @@ -37,8 +37,8 @@ static unsigned char icon_bits[] = { 0x00, 0x00, 0x1C, 0x00, 0x70, 0x00, 0x00, 0x1C, 0x00, 0x70, 0x00, 0x00, 0x1C, 0x00, 0x70, 0x00, 0x00, 0x1C, 0x00}; */ /* -#define ADMIN_KEY_USERPREFS 1 -static unsigned char admin_key_userprefs[] = {0xcd, 0xc0, 0xb4, 0x3c, 0x53, 0x24, 0xdf, 0x13, 0xca, 0x5a, 0xa6, +#define USERPREFS_USE_ADMIN_KEY 1 +static unsigned char USERPREFS_ADMIN_KEY[] = {0xcd, 0xc0, 0xb4, 0x3c, 0x53, 0x24, 0xdf, 0x13, 0xca, 0x5a, 0xa6, 0x0c, 0x0d, 0xec, 0x85, 0x5a, 0x4c, 0xf6, 0x1a, 0x96, 0x04, 0x1a, 0x3e, 0xfc, 0xbb, 0x8e, 0x33, 0x71, 0xe5, 0xfc, 0xff, 0x3c}; */ From 0a93261c0646f93aea518cc0599e547e9dc0e997 Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Wed, 2 Oct 2024 06:14:55 -0500 Subject: [PATCH 45/88] [create-pull-request] automated change (#4926) Co-authored-by: thebentern <9000580+thebentern@users.noreply.github.com> --- protobufs | 2 +- src/mesh/generated/meshtastic/deviceonly.pb.h | 2 +- src/mesh/generated/meshtastic/localonly.pb.h | 2 +- .../generated/meshtastic/module_config.pb.h | 18 ++++++-- .../generated/meshtastic/telemetry.pb.cpp | 3 ++ src/mesh/generated/meshtastic/telemetry.pb.h | 44 +++++++++++++++++-- 6 files changed, 60 insertions(+), 11 deletions(-) diff --git a/protobufs b/protobufs index 61d7ca656..62c4b0081 160000 --- a/protobufs +++ b/protobufs @@ -1 +1 @@ -Subproject commit 61d7ca65652dfe832ead74719700d3d33d6bae7c +Subproject commit 62c4b0081c8217a139484a24a47e9b35e133ebf3 diff --git a/src/mesh/generated/meshtastic/deviceonly.pb.h b/src/mesh/generated/meshtastic/deviceonly.pb.h index a905c4526..0fc09daca 100644 --- a/src/mesh/generated/meshtastic/deviceonly.pb.h +++ b/src/mesh/generated/meshtastic/deviceonly.pb.h @@ -359,7 +359,7 @@ extern const pb_msgdesc_t meshtastic_OEMStore_msg; #define MESHTASTIC_MESHTASTIC_DEVICEONLY_PB_H_MAX_SIZE meshtastic_OEMStore_size #define meshtastic_ChannelFile_size 718 #define meshtastic_NodeInfoLite_size 183 -#define meshtastic_OEMStore_size 3568 +#define meshtastic_OEMStore_size 3576 #define meshtastic_PositionLite_size 28 #define meshtastic_UserLite_size 96 diff --git a/src/mesh/generated/meshtastic/localonly.pb.h b/src/mesh/generated/meshtastic/localonly.pb.h index 19600856f..bac67942c 100644 --- a/src/mesh/generated/meshtastic/localonly.pb.h +++ b/src/mesh/generated/meshtastic/localonly.pb.h @@ -188,7 +188,7 @@ extern const pb_msgdesc_t meshtastic_LocalModuleConfig_msg; /* Maximum encoded size of messages (where known) */ #define MESHTASTIC_MESHTASTIC_LOCALONLY_PB_H_MAX_SIZE meshtastic_LocalConfig_size #define meshtastic_LocalConfig_size 735 -#define meshtastic_LocalModuleConfig_size 687 +#define meshtastic_LocalModuleConfig_size 695 #ifdef __cplusplus } /* extern "C" */ diff --git a/src/mesh/generated/meshtastic/module_config.pb.h b/src/mesh/generated/meshtastic/module_config.pb.h index d4b82c93b..ce8b8891a 100644 --- a/src/mesh/generated/meshtastic/module_config.pb.h +++ b/src/mesh/generated/meshtastic/module_config.pb.h @@ -336,6 +336,12 @@ typedef struct _meshtastic_ModuleConfig_TelemetryConfig { /* Interval in seconds of how often we should try to send our air quality metrics to the mesh */ bool power_screen_enabled; + /* Preferences for the (Health) Telemetry Module + Enable/Disable the telemetry measurement module measurement collection */ + bool health_measurement_enabled; + /* Interval in seconds of how often we should try to send our + health metrics to the mesh */ + uint32_t health_update_interval; } meshtastic_ModuleConfig_TelemetryConfig; /* TODO: REPLACE */ @@ -503,7 +509,7 @@ extern "C" { #define meshtastic_ModuleConfig_ExternalNotificationConfig_init_default {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} #define meshtastic_ModuleConfig_StoreForwardConfig_init_default {0, 0, 0, 0, 0, 0} #define meshtastic_ModuleConfig_RangeTestConfig_init_default {0, 0, 0} -#define meshtastic_ModuleConfig_TelemetryConfig_init_default {0, 0, 0, 0, 0, 0, 0, 0, 0, 0} +#define meshtastic_ModuleConfig_TelemetryConfig_init_default {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} #define meshtastic_ModuleConfig_CannedMessageConfig_init_default {0, 0, 0, 0, _meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_MIN, _meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_MIN, _meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_MIN, 0, 0, "", 0} #define meshtastic_ModuleConfig_AmbientLightingConfig_init_default {0, 0, 0, 0, 0} #define meshtastic_RemoteHardwarePin_init_default {0, "", _meshtastic_RemoteHardwarePinType_MIN} @@ -519,7 +525,7 @@ extern "C" { #define meshtastic_ModuleConfig_ExternalNotificationConfig_init_zero {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} #define meshtastic_ModuleConfig_StoreForwardConfig_init_zero {0, 0, 0, 0, 0, 0} #define meshtastic_ModuleConfig_RangeTestConfig_init_zero {0, 0, 0} -#define meshtastic_ModuleConfig_TelemetryConfig_init_zero {0, 0, 0, 0, 0, 0, 0, 0, 0, 0} +#define meshtastic_ModuleConfig_TelemetryConfig_init_zero {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} #define meshtastic_ModuleConfig_CannedMessageConfig_init_zero {0, 0, 0, 0, _meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_MIN, _meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_MIN, _meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_MIN, 0, 0, "", 0} #define meshtastic_ModuleConfig_AmbientLightingConfig_init_zero {0, 0, 0, 0, 0} #define meshtastic_RemoteHardwarePin_init_zero {0, "", _meshtastic_RemoteHardwarePinType_MIN} @@ -601,6 +607,8 @@ extern "C" { #define meshtastic_ModuleConfig_TelemetryConfig_power_measurement_enabled_tag 8 #define meshtastic_ModuleConfig_TelemetryConfig_power_update_interval_tag 9 #define meshtastic_ModuleConfig_TelemetryConfig_power_screen_enabled_tag 10 +#define meshtastic_ModuleConfig_TelemetryConfig_health_measurement_enabled_tag 11 +#define meshtastic_ModuleConfig_TelemetryConfig_health_update_interval_tag 12 #define meshtastic_ModuleConfig_CannedMessageConfig_rotary1_enabled_tag 1 #define meshtastic_ModuleConfig_CannedMessageConfig_inputbroker_pin_a_tag 2 #define meshtastic_ModuleConfig_CannedMessageConfig_inputbroker_pin_b_tag 3 @@ -793,7 +801,9 @@ X(a, STATIC, SINGULAR, BOOL, air_quality_enabled, 6) \ X(a, STATIC, SINGULAR, UINT32, air_quality_interval, 7) \ X(a, STATIC, SINGULAR, BOOL, power_measurement_enabled, 8) \ X(a, STATIC, SINGULAR, UINT32, power_update_interval, 9) \ -X(a, STATIC, SINGULAR, BOOL, power_screen_enabled, 10) +X(a, STATIC, SINGULAR, BOOL, power_screen_enabled, 10) \ +X(a, STATIC, SINGULAR, BOOL, health_measurement_enabled, 11) \ +X(a, STATIC, SINGULAR, UINT32, health_update_interval, 12) #define meshtastic_ModuleConfig_TelemetryConfig_CALLBACK NULL #define meshtastic_ModuleConfig_TelemetryConfig_DEFAULT NULL @@ -878,7 +888,7 @@ extern const pb_msgdesc_t meshtastic_RemoteHardwarePin_msg; #define meshtastic_ModuleConfig_RemoteHardwareConfig_size 96 #define meshtastic_ModuleConfig_SerialConfig_size 28 #define meshtastic_ModuleConfig_StoreForwardConfig_size 24 -#define meshtastic_ModuleConfig_TelemetryConfig_size 36 +#define meshtastic_ModuleConfig_TelemetryConfig_size 44 #define meshtastic_ModuleConfig_size 257 #define meshtastic_RemoteHardwarePin_size 21 diff --git a/src/mesh/generated/meshtastic/telemetry.pb.cpp b/src/mesh/generated/meshtastic/telemetry.pb.cpp index 90859c98e..b9c1da7a0 100644 --- a/src/mesh/generated/meshtastic/telemetry.pb.cpp +++ b/src/mesh/generated/meshtastic/telemetry.pb.cpp @@ -21,6 +21,9 @@ PB_BIND(meshtastic_AirQualityMetrics, meshtastic_AirQualityMetrics, AUTO) PB_BIND(meshtastic_LocalStats, meshtastic_LocalStats, AUTO) +PB_BIND(meshtastic_HealthMetrics, meshtastic_HealthMetrics, AUTO) + + PB_BIND(meshtastic_Telemetry, meshtastic_Telemetry, AUTO) diff --git a/src/mesh/generated/meshtastic/telemetry.pb.h b/src/mesh/generated/meshtastic/telemetry.pb.h index cedc2867e..61897fc5c 100644 --- a/src/mesh/generated/meshtastic/telemetry.pb.h +++ b/src/mesh/generated/meshtastic/telemetry.pb.h @@ -71,7 +71,9 @@ typedef enum _meshtastic_TelemetrySensorType { /* MAX17048 1S lipo battery sensor (voltage, state of charge, time to go) */ meshtastic_TelemetrySensorType_MAX17048 = 28, /* Custom I2C sensor implementation based on https://github.com/meshtastic/i2c-sensor */ - meshtastic_TelemetrySensorType_CUSTOM_SENSOR = 29 + meshtastic_TelemetrySensorType_CUSTOM_SENSOR = 29, + /* MAX30102 Pulse Oximeter and Heart-Rate Sensor */ + meshtastic_TelemetrySensorType_MAX30102 = 30 } meshtastic_TelemetrySensorType; /* Struct definitions */ @@ -233,6 +235,19 @@ typedef struct _meshtastic_LocalStats { uint16_t num_total_nodes; } meshtastic_LocalStats; +/* Health telemetry metrics */ +typedef struct _meshtastic_HealthMetrics { + /* Heart rate (beats per minute) */ + bool has_heart_bpm; + uint8_t heart_bpm; + /* SpO2 (blood oxygen saturation) level */ + bool has_spO2; + uint8_t spO2; + /* Body temperature in degrees Celsius */ + bool has_temperature; + float temperature; +} meshtastic_HealthMetrics; + /* Types of Measurements the telemetry module is equipped to handle */ typedef struct _meshtastic_Telemetry { /* Seconds since 1970 - or 0 for unknown/unset */ @@ -249,6 +264,8 @@ typedef struct _meshtastic_Telemetry { meshtastic_PowerMetrics power_metrics; /* Local device mesh statistics */ meshtastic_LocalStats local_stats; + /* Health telemetry metrics */ + meshtastic_HealthMetrics health_metrics; } variant; } meshtastic_Telemetry; @@ -267,8 +284,9 @@ extern "C" { /* Helper constants for enums */ #define _meshtastic_TelemetrySensorType_MIN meshtastic_TelemetrySensorType_SENSOR_UNSET -#define _meshtastic_TelemetrySensorType_MAX meshtastic_TelemetrySensorType_CUSTOM_SENSOR -#define _meshtastic_TelemetrySensorType_ARRAYSIZE ((meshtastic_TelemetrySensorType)(meshtastic_TelemetrySensorType_CUSTOM_SENSOR+1)) +#define _meshtastic_TelemetrySensorType_MAX meshtastic_TelemetrySensorType_MAX30102 +#define _meshtastic_TelemetrySensorType_ARRAYSIZE ((meshtastic_TelemetrySensorType)(meshtastic_TelemetrySensorType_MAX30102+1)) + @@ -284,6 +302,7 @@ extern "C" { #define meshtastic_PowerMetrics_init_default {false, 0, false, 0, false, 0, false, 0, false, 0, false, 0} #define meshtastic_AirQualityMetrics_init_default {false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0} #define meshtastic_LocalStats_init_default {0, 0, 0, 0, 0, 0, 0, 0} +#define meshtastic_HealthMetrics_init_default {false, 0, false, 0, false, 0} #define meshtastic_Telemetry_init_default {0, 0, {meshtastic_DeviceMetrics_init_default}} #define meshtastic_Nau7802Config_init_default {0, 0} #define meshtastic_DeviceMetrics_init_zero {false, 0, false, 0, false, 0, false, 0, false, 0} @@ -291,6 +310,7 @@ extern "C" { #define meshtastic_PowerMetrics_init_zero {false, 0, false, 0, false, 0, false, 0, false, 0, false, 0} #define meshtastic_AirQualityMetrics_init_zero {false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0} #define meshtastic_LocalStats_init_zero {0, 0, 0, 0, 0, 0, 0, 0} +#define meshtastic_HealthMetrics_init_zero {false, 0, false, 0, false, 0} #define meshtastic_Telemetry_init_zero {0, 0, {meshtastic_DeviceMetrics_init_zero}} #define meshtastic_Nau7802Config_init_zero {0, 0} @@ -343,12 +363,16 @@ extern "C" { #define meshtastic_LocalStats_num_packets_rx_bad_tag 6 #define meshtastic_LocalStats_num_online_nodes_tag 7 #define meshtastic_LocalStats_num_total_nodes_tag 8 +#define meshtastic_HealthMetrics_heart_bpm_tag 1 +#define meshtastic_HealthMetrics_spO2_tag 2 +#define meshtastic_HealthMetrics_temperature_tag 3 #define meshtastic_Telemetry_time_tag 1 #define meshtastic_Telemetry_device_metrics_tag 2 #define meshtastic_Telemetry_environment_metrics_tag 3 #define meshtastic_Telemetry_air_quality_metrics_tag 4 #define meshtastic_Telemetry_power_metrics_tag 5 #define meshtastic_Telemetry_local_stats_tag 6 +#define meshtastic_Telemetry_health_metrics_tag 7 #define meshtastic_Nau7802Config_zeroOffset_tag 1 #define meshtastic_Nau7802Config_calibrationFactor_tag 2 @@ -421,13 +445,21 @@ X(a, STATIC, SINGULAR, UINT32, num_total_nodes, 8) #define meshtastic_LocalStats_CALLBACK NULL #define meshtastic_LocalStats_DEFAULT NULL +#define meshtastic_HealthMetrics_FIELDLIST(X, a) \ +X(a, STATIC, OPTIONAL, UINT32, heart_bpm, 1) \ +X(a, STATIC, OPTIONAL, UINT32, spO2, 2) \ +X(a, STATIC, OPTIONAL, FLOAT, temperature, 3) +#define meshtastic_HealthMetrics_CALLBACK NULL +#define meshtastic_HealthMetrics_DEFAULT NULL + #define meshtastic_Telemetry_FIELDLIST(X, a) \ X(a, STATIC, SINGULAR, FIXED32, time, 1) \ X(a, STATIC, ONEOF, MESSAGE, (variant,device_metrics,variant.device_metrics), 2) \ X(a, STATIC, ONEOF, MESSAGE, (variant,environment_metrics,variant.environment_metrics), 3) \ X(a, STATIC, ONEOF, MESSAGE, (variant,air_quality_metrics,variant.air_quality_metrics), 4) \ X(a, STATIC, ONEOF, MESSAGE, (variant,power_metrics,variant.power_metrics), 5) \ -X(a, STATIC, ONEOF, MESSAGE, (variant,local_stats,variant.local_stats), 6) +X(a, STATIC, ONEOF, MESSAGE, (variant,local_stats,variant.local_stats), 6) \ +X(a, STATIC, ONEOF, MESSAGE, (variant,health_metrics,variant.health_metrics), 7) #define meshtastic_Telemetry_CALLBACK NULL #define meshtastic_Telemetry_DEFAULT NULL #define meshtastic_Telemetry_variant_device_metrics_MSGTYPE meshtastic_DeviceMetrics @@ -435,6 +467,7 @@ X(a, STATIC, ONEOF, MESSAGE, (variant,local_stats,variant.local_stats), #define meshtastic_Telemetry_variant_air_quality_metrics_MSGTYPE meshtastic_AirQualityMetrics #define meshtastic_Telemetry_variant_power_metrics_MSGTYPE meshtastic_PowerMetrics #define meshtastic_Telemetry_variant_local_stats_MSGTYPE meshtastic_LocalStats +#define meshtastic_Telemetry_variant_health_metrics_MSGTYPE meshtastic_HealthMetrics #define meshtastic_Nau7802Config_FIELDLIST(X, a) \ X(a, STATIC, SINGULAR, INT32, zeroOffset, 1) \ @@ -447,6 +480,7 @@ extern const pb_msgdesc_t meshtastic_EnvironmentMetrics_msg; extern const pb_msgdesc_t meshtastic_PowerMetrics_msg; extern const pb_msgdesc_t meshtastic_AirQualityMetrics_msg; extern const pb_msgdesc_t meshtastic_LocalStats_msg; +extern const pb_msgdesc_t meshtastic_HealthMetrics_msg; extern const pb_msgdesc_t meshtastic_Telemetry_msg; extern const pb_msgdesc_t meshtastic_Nau7802Config_msg; @@ -456,6 +490,7 @@ extern const pb_msgdesc_t meshtastic_Nau7802Config_msg; #define meshtastic_PowerMetrics_fields &meshtastic_PowerMetrics_msg #define meshtastic_AirQualityMetrics_fields &meshtastic_AirQualityMetrics_msg #define meshtastic_LocalStats_fields &meshtastic_LocalStats_msg +#define meshtastic_HealthMetrics_fields &meshtastic_HealthMetrics_msg #define meshtastic_Telemetry_fields &meshtastic_Telemetry_msg #define meshtastic_Nau7802Config_fields &meshtastic_Nau7802Config_msg @@ -464,6 +499,7 @@ extern const pb_msgdesc_t meshtastic_Nau7802Config_msg; #define meshtastic_AirQualityMetrics_size 72 #define meshtastic_DeviceMetrics_size 27 #define meshtastic_EnvironmentMetrics_size 85 +#define meshtastic_HealthMetrics_size 11 #define meshtastic_LocalStats_size 42 #define meshtastic_Nau7802Config_size 16 #define meshtastic_PowerMetrics_size 30 From 07d4e6f5beadbd36ef54d1fba49f14ceb6fc09fe Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Thu, 3 Oct 2024 07:57:34 -0500 Subject: [PATCH 46/88] Bump protobufs from `62c4b00` to `b419706` (#4934) Bumps [protobufs](https://github.com/meshtastic/protobufs) from `62c4b00` to `b419706`. - [Release notes](https://github.com/meshtastic/protobufs/releases) - [Commits](https://github.com/meshtastic/protobufs/compare/62c4b0081c8217a139484a24a47e9b35e133ebf3...b419706693e0120f7b032d0be0121ae758cfd6e4) --- updated-dependencies: - dependency-name: protobufs dependency-type: direct:production ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- protobufs | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/protobufs b/protobufs index 62c4b0081..b41970669 160000 --- a/protobufs +++ b/protobufs @@ -1 +1 @@ -Subproject commit 62c4b0081c8217a139484a24a47e9b35e133ebf3 +Subproject commit b419706693e0120f7b032d0be0121ae758cfd6e4 From b2b60eccdbe1d1732859ad52ae05d6c05fbdc7ef Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Thu, 3 Oct 2024 14:54:18 -0500 Subject: [PATCH 47/88] [create-pull-request] automated change (#4937) Co-authored-by: GUVWAF <78759985+GUVWAF@users.noreply.github.com> --- src/mesh/generated/meshtastic/telemetry.pb.h | 32 +++++++++++++++----- 1 file changed, 24 insertions(+), 8 deletions(-) diff --git a/src/mesh/generated/meshtastic/telemetry.pb.h b/src/mesh/generated/meshtastic/telemetry.pb.h index 61897fc5c..cbe71ed52 100644 --- a/src/mesh/generated/meshtastic/telemetry.pb.h +++ b/src/mesh/generated/meshtastic/telemetry.pb.h @@ -73,7 +73,9 @@ typedef enum _meshtastic_TelemetrySensorType { /* Custom I2C sensor implementation based on https://github.com/meshtastic/i2c-sensor */ meshtastic_TelemetrySensorType_CUSTOM_SENSOR = 29, /* MAX30102 Pulse Oximeter and Heart-Rate Sensor */ - meshtastic_TelemetrySensorType_MAX30102 = 30 + meshtastic_TelemetrySensorType_MAX30102 = 30, + /* MLX90614 non-contact IR temperature sensor. */ + meshtastic_TelemetrySensorType_MLX90614 = 31 } meshtastic_TelemetrySensorType; /* Struct definitions */ @@ -225,7 +227,7 @@ typedef struct _meshtastic_LocalStats { float air_util_tx; /* Number of packets sent */ uint32_t num_packets_tx; - /* Number of packets received good */ + /* Number of packets received (both good and bad) */ uint32_t num_packets_rx; /* Number of packets received that are malformed or violate the protocol */ uint32_t num_packets_rx_bad; @@ -233,6 +235,14 @@ typedef struct _meshtastic_LocalStats { uint16_t num_online_nodes; /* Number of nodes total */ uint16_t num_total_nodes; + /* Number of received packets that were duplicates (due to multiple nodes relaying). + If this number is high, there are nodes in the mesh relaying packets when it's unnecessary, for example due to the ROUTER/REPEATER role. */ + uint32_t num_rx_dupe; + /* Number of packets we transmitted that were a relay for others (not originating from ourselves). */ + uint32_t num_tx_relay; + /* Number of times we canceled a packet to be relayed, because someone else did it before us. + This will always be zero for ROUTERs/REPEATERs. If this number is high, some other node(s) is/are relaying faster than you. */ + uint32_t num_tx_relay_canceled; } meshtastic_LocalStats; /* Health telemetry metrics */ @@ -284,8 +294,8 @@ extern "C" { /* Helper constants for enums */ #define _meshtastic_TelemetrySensorType_MIN meshtastic_TelemetrySensorType_SENSOR_UNSET -#define _meshtastic_TelemetrySensorType_MAX meshtastic_TelemetrySensorType_MAX30102 -#define _meshtastic_TelemetrySensorType_ARRAYSIZE ((meshtastic_TelemetrySensorType)(meshtastic_TelemetrySensorType_MAX30102+1)) +#define _meshtastic_TelemetrySensorType_MAX meshtastic_TelemetrySensorType_MLX90614 +#define _meshtastic_TelemetrySensorType_ARRAYSIZE ((meshtastic_TelemetrySensorType)(meshtastic_TelemetrySensorType_MLX90614+1)) @@ -301,7 +311,7 @@ extern "C" { #define meshtastic_EnvironmentMetrics_init_default {false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0} #define meshtastic_PowerMetrics_init_default {false, 0, false, 0, false, 0, false, 0, false, 0, false, 0} #define meshtastic_AirQualityMetrics_init_default {false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0} -#define meshtastic_LocalStats_init_default {0, 0, 0, 0, 0, 0, 0, 0} +#define meshtastic_LocalStats_init_default {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} #define meshtastic_HealthMetrics_init_default {false, 0, false, 0, false, 0} #define meshtastic_Telemetry_init_default {0, 0, {meshtastic_DeviceMetrics_init_default}} #define meshtastic_Nau7802Config_init_default {0, 0} @@ -309,7 +319,7 @@ extern "C" { #define meshtastic_EnvironmentMetrics_init_zero {false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0} #define meshtastic_PowerMetrics_init_zero {false, 0, false, 0, false, 0, false, 0, false, 0, false, 0} #define meshtastic_AirQualityMetrics_init_zero {false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0} -#define meshtastic_LocalStats_init_zero {0, 0, 0, 0, 0, 0, 0, 0} +#define meshtastic_LocalStats_init_zero {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} #define meshtastic_HealthMetrics_init_zero {false, 0, false, 0, false, 0} #define meshtastic_Telemetry_init_zero {0, 0, {meshtastic_DeviceMetrics_init_zero}} #define meshtastic_Nau7802Config_init_zero {0, 0} @@ -363,6 +373,9 @@ extern "C" { #define meshtastic_LocalStats_num_packets_rx_bad_tag 6 #define meshtastic_LocalStats_num_online_nodes_tag 7 #define meshtastic_LocalStats_num_total_nodes_tag 8 +#define meshtastic_LocalStats_num_rx_dupe_tag 9 +#define meshtastic_LocalStats_num_tx_relay_tag 10 +#define meshtastic_LocalStats_num_tx_relay_canceled_tag 11 #define meshtastic_HealthMetrics_heart_bpm_tag 1 #define meshtastic_HealthMetrics_spO2_tag 2 #define meshtastic_HealthMetrics_temperature_tag 3 @@ -441,7 +454,10 @@ X(a, STATIC, SINGULAR, UINT32, num_packets_tx, 4) \ X(a, STATIC, SINGULAR, UINT32, num_packets_rx, 5) \ X(a, STATIC, SINGULAR, UINT32, num_packets_rx_bad, 6) \ X(a, STATIC, SINGULAR, UINT32, num_online_nodes, 7) \ -X(a, STATIC, SINGULAR, UINT32, num_total_nodes, 8) +X(a, STATIC, SINGULAR, UINT32, num_total_nodes, 8) \ +X(a, STATIC, SINGULAR, UINT32, num_rx_dupe, 9) \ +X(a, STATIC, SINGULAR, UINT32, num_tx_relay, 10) \ +X(a, STATIC, SINGULAR, UINT32, num_tx_relay_canceled, 11) #define meshtastic_LocalStats_CALLBACK NULL #define meshtastic_LocalStats_DEFAULT NULL @@ -500,7 +516,7 @@ extern const pb_msgdesc_t meshtastic_Nau7802Config_msg; #define meshtastic_DeviceMetrics_size 27 #define meshtastic_EnvironmentMetrics_size 85 #define meshtastic_HealthMetrics_size 11 -#define meshtastic_LocalStats_size 42 +#define meshtastic_LocalStats_size 60 #define meshtastic_Nau7802Config_size 16 #define meshtastic_PowerMetrics_size 30 #define meshtastic_Telemetry_size 92 From befc2ece6f06f6002e5ce3128df3c4c82aa538fe Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Thu, 3 Oct 2024 20:51:22 -0500 Subject: [PATCH 48/88] Add a Userprefs Timezone String, to be replaced in the web flasher (#4938) * Add a Userprefs Timezone String, to be replaced in the web flasher * Use a volatile char buffer for slipstreamed strings. * More refinement --- src/main.cpp | 11 +++++++++-- userPrefs.h | 2 +- 2 files changed, 10 insertions(+), 3 deletions(-) diff --git a/src/main.cpp b/src/main.cpp index c11995837..a8ea69111 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -1,3 +1,4 @@ +#include "../userPrefs.h" #include "configuration.h" #if !MESHTASTIC_EXCLUDE_GPS #include "GPS.h" @@ -706,10 +707,16 @@ void setup() // setup TZ prior to time actions. #if !MESHTASTIC_EXCLUDE_TZ - if (*config.device.tzdef) { + LOG_DEBUG("Using compiled/slipstreamed %s\n", USERPREFS_TZ_STRING); // important, removing this clobbers our magic string + if (*config.device.tzdef && config.device.tzdef[0] != 0) { + LOG_DEBUG("Saved TZ: %s \n", config.device.tzdef); setenv("TZ", config.device.tzdef, 1); } else { - setenv("TZ", "GMT0", 1); + if (strncmp((const char *)USERPREFS_TZ_STRING, "tzpl", 4) == 0) { + setenv("TZ", "GMT0", 1); + } else { + setenv("TZ", (const char *)USERPREFS_TZ_STRING, 1); + } } tzset(); LOG_DEBUG("Set Timezone to %s\n", getenv("TZ")); diff --git a/userPrefs.h b/userPrefs.h index 40f2cc6d2..337bd7976 100644 --- a/userPrefs.h +++ b/userPrefs.h @@ -1,6 +1,6 @@ #ifndef _USERPREFS_ #define _USERPREFS_ - +volatile static const char USERPREFS_TZ_STRING[] = "tzplaceholder "; // Uncomment and modify to set device defaults // #define USERPREFS_EVENT_MODE 1 From d6f26c682d05163d971d81af141ccf814dfa807c Mon Sep 17 00:00:00 2001 From: HarukiToreda <116696711+HarukiToreda@users.noreply.github.com> Date: Fri, 4 Oct 2024 07:15:59 -0400 Subject: [PATCH 49/88] Enabling Ve pin on T114 (#4940) * Enabling Ve pin on T114 Problem: The Ve pin was not enabled in the firmware, and it was supposed to control the power to the GPS via the GPS_EN pin. As a result, users were forced to rely on the 3.3V pin to power their additional peripherals, which caused a constant power draw from the battery, even when the node was in deep sleep mode. Solution: To resolve this, Todd_Hervert and I decided to remove the GPS power toggle after testing revealed that the GPS only consumes 1mA in soft sleep mode. This minimal power consumption allowed us to enable the Ve pin without causing significant battery drain. Additionally, we added a delay to the I2C initialization process, as the Ve pin requires a few milliseconds to stabilize, which could prevent some peripherals from booting up in time. Result: The GPS operates as usual, drawing only 1mA of power. The keyboard and other peripherals attached to the Ve pin now power off correctly when the node is shut down. The I2C check initiates without issues after the delay, allowing all peripherals to function smoothly. * trunk format --------- Co-authored-by: Tom Fifield --- variants/heltec_mesh_node_t114/variant.h | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/variants/heltec_mesh_node_t114/variant.h b/variants/heltec_mesh_node_t114/variant.h index 2cea3ef2f..426085a26 100644 --- a/variants/heltec_mesh_node_t114/variant.h +++ b/variants/heltec_mesh_node_t114/variant.h @@ -154,8 +154,11 @@ No longer populated on PCB // #define PIN_GPS_RESET (32 + 6) // An output to reset L76K GPS. As per datasheet, low for > 100ms will reset the L76K #define GPS_RESET_MODE LOW -#define PIN_GPS_EN (21) -#define GPS_EN_ACTIVE HIGH +// #define PIN_GPS_EN (21) +#define VEXT_ENABLE (0 + 21) +#define PERIPHERAL_WARMUP_MS 1000 // Make sure I2C QuickLink has stable power before continuing +#define VEXT_ON_VALUE HIGH +// #define GPS_EN_ACTIVE HIGH #define PIN_GPS_STANDBY (32 + 2) // An output to wake GPS, low means allow sleep, high means force wake #define PIN_GPS_PPS (32 + 4) // Seems to be missing on this new board From 236374491b36248d36519392d5d58ef4cadab9a7 Mon Sep 17 00:00:00 2001 From: gitbisector Date: Fri, 4 Oct 2024 04:17:23 -0700 Subject: [PATCH 50/88] cleanupNeighbors() time difference fix (#4941) --- src/modules/NeighborInfoModule.cpp | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/src/modules/NeighborInfoModule.cpp b/src/modules/NeighborInfoModule.cpp index 55ed46b5e..e4c9b44bd 100644 --- a/src/modules/NeighborInfoModule.cpp +++ b/src/modules/NeighborInfoModule.cpp @@ -62,7 +62,8 @@ uint32_t NeighborInfoModule::collectNeighborInfo(meshtastic_NeighborInfo *neighb NodeNum my_node_id = nodeDB->getNodeNum(); neighborInfo->node_id = my_node_id; neighborInfo->last_sent_by_id = my_node_id; - neighborInfo->node_broadcast_interval_secs = moduleConfig.neighbor_info.update_interval; + neighborInfo->node_broadcast_interval_secs = + Default::getConfiguredOrDefault(moduleConfig.neighbor_info.update_interval, default_telemetry_broadcast_interval_secs); cleanUpNeighbors(); @@ -84,11 +85,12 @@ uint32_t NeighborInfoModule::collectNeighborInfo(meshtastic_NeighborInfo *neighb */ void NeighborInfoModule::cleanUpNeighbors() { + uint32_t now = getTime(); NodeNum my_node_id = nodeDB->getNodeNum(); for (auto it = neighbors.rbegin(); it != neighbors.rend();) { // We will remove a neighbor if we haven't heard from them in twice the broadcast interval - if (!Throttle::isWithinTimespanMs(it->last_rx_time, it->node_broadcast_interval_secs * 2) && - (it->node_id != my_node_id)) { + // cannot use isWithinTimespanMs() as it->last_rx_time is seconds since 1970 + if ((now - it->last_rx_time > it->node_broadcast_interval_secs * 2) && (it->node_id != my_node_id)) { LOG_DEBUG("Removing neighbor with node ID 0x%x\n", it->node_id); it = std::vector::reverse_iterator( neighbors.erase(std::next(it).base())); // Erase the element and update the iterator From 673fe294f346faf160ff2de2cab6cdf8bd500d7e Mon Sep 17 00:00:00 2001 From: GUVWAF <78759985+GUVWAF@users.noreply.github.com> Date: Fri, 4 Oct 2024 13:28:51 +0200 Subject: [PATCH 51/88] Add `rxDupe`, `txRelay` and `txRelayCanceled` to LocalStats (#4936) * Introduce `isFromUs()` and `isToUs()` * Add rxDupe, txRelay and txRelayCanceled to LocalStats --- src/mesh/FloodingRouter.cpp | 8 +++++--- src/mesh/MeshModule.cpp | 5 ++--- src/mesh/MeshPacketQueue.cpp | 2 +- src/mesh/MeshTypes.h | 6 ++++++ src/mesh/NodeDB.cpp | 12 ++++++++++++ src/mesh/RadioLibInterface.cpp | 4 +++- src/mesh/RadioLibInterface.h | 2 +- src/mesh/ReliableRouter.cpp | 6 ++---- src/mesh/Router.cpp | 20 ++++++++++---------- src/mesh/Router.h | 4 ++++ src/modules/AdminModule.cpp | 2 +- src/modules/ExternalNotificationModule.cpp | 4 ++-- src/modules/NodeInfoModule.cpp | 2 +- src/modules/PositionModule.cpp | 4 ++-- src/modules/RangeTestModule.cpp | 2 +- src/modules/RoutingModule.cpp | 2 +- src/modules/SerialModule.cpp | 2 +- src/modules/StoreForwardModule.cpp | 7 +++---- src/modules/Telemetry/DeviceTelemetry.cpp | 5 +++++ src/modules/TraceRouteModule.cpp | 4 ++-- src/modules/esp32/AudioModule.cpp | 2 +- src/mqtt/MQTT.cpp | 10 +++++----- 22 files changed, 71 insertions(+), 44 deletions(-) diff --git a/src/mesh/FloodingRouter.cpp b/src/mesh/FloodingRouter.cpp index 037fdd2ae..23f6b6f92 100644 --- a/src/mesh/FloodingRouter.cpp +++ b/src/mesh/FloodingRouter.cpp @@ -22,10 +22,12 @@ bool FloodingRouter::shouldFilterReceived(const meshtastic_MeshPacket *p) { if (wasSeenRecently(p)) { // Note: this will also add a recent packet record printPacket("Ignoring dupe incoming msg", p); + rxDupe++; if (config.device.role != meshtastic_Config_DeviceConfig_Role_ROUTER && config.device.role != meshtastic_Config_DeviceConfig_Role_REPEATER) { // cancel rebroadcast of this message *if* there was already one, unless we're a router/repeater! - Router::cancelSending(p->from, p->id); + if (Router::cancelSending(p->from, p->id)) + txRelayCanceled++; } return true; } @@ -36,12 +38,12 @@ bool FloodingRouter::shouldFilterReceived(const meshtastic_MeshPacket *p) void FloodingRouter::sniffReceived(const meshtastic_MeshPacket *p, const meshtastic_Routing *c) { bool isAckorReply = (p->which_payload_variant == meshtastic_MeshPacket_decoded_tag) && (p->decoded.request_id != 0); - if (isAckorReply && p->to != getNodeNum() && p->to != NODENUM_BROADCAST) { + if (isAckorReply && !isToUs(p) && p->to != NODENUM_BROADCAST) { // do not flood direct message that is ACKed or replied to LOG_DEBUG("Rxd an ACK/reply not for me, cancel rebroadcast.\n"); Router::cancelSending(p->to, p->decoded.request_id); // cancel rebroadcast for this DM } - if ((p->to != getNodeNum()) && (p->hop_limit > 0) && (getFrom(p) != getNodeNum())) { + if (!isToUs(p) && (p->hop_limit > 0) && !isFromUs(p)) { if (p->id != 0) { if (config.device.role != meshtastic_Config_DeviceConfig_Role_CLIENT_MUTE) { meshtastic_MeshPacket *tosend = packetPool.allocCopy(*p); // keep a copy because we will be sending it diff --git a/src/mesh/MeshModule.cpp b/src/mesh/MeshModule.cpp index 3b137d4bd..27aca5832 100644 --- a/src/mesh/MeshModule.cpp +++ b/src/mesh/MeshModule.cpp @@ -86,7 +86,7 @@ void MeshModule::callModules(meshtastic_MeshPacket &mp, RxSource src) // Was this message directed to us specifically? Will be false if we are sniffing someone elses packets auto ourNodeNum = nodeDB->getNodeNum(); - bool toUs = mp.to == NODENUM_BROADCAST || mp.to == ourNodeNum; + bool toUs = mp.to == NODENUM_BROADCAST || isToUs(&mp); for (auto i = modules->begin(); i != modules->end(); ++i) { auto &pi = **i; @@ -141,8 +141,7 @@ void MeshModule::callModules(meshtastic_MeshPacket &mp, RxSource src) // because currently when the phone sends things, it sends things using the local node ID as the from address. A // better solution (FIXME) would be to let phones have their own distinct addresses and we 'route' to them like // any other node. - if (isDecoded && mp.decoded.want_response && toUs && (getFrom(&mp) != ourNodeNum || mp.to == ourNodeNum) && - !currentReply) { + if (isDecoded && mp.decoded.want_response && toUs && (!isFromUs(&mp) || isToUs(&mp)) && !currentReply) { pi.sendResponse(mp); ignoreRequest = ignoreRequest || pi.ignoreRequest; // If at least one module asks it, we may ignore a request LOG_INFO("Asked module '%s' to send a response\n", pi.name); diff --git a/src/mesh/MeshPacketQueue.cpp b/src/mesh/MeshPacketQueue.cpp index da49ecb61..99ef41c1e 100644 --- a/src/mesh/MeshPacketQueue.cpp +++ b/src/mesh/MeshPacketQueue.cpp @@ -19,7 +19,7 @@ bool CompareMeshPacketFunc(const meshtastic_MeshPacket *p1, const meshtastic_Mes auto p1p = getPriority(p1), p2p = getPriority(p2); // If priorities differ, use that // for equal priorities, prefer packets already on mesh. - return (p1p != p2p) ? (p1p > p2p) : (getFrom(p1) != nodeDB->getNodeNum() && getFrom(p2) == nodeDB->getNodeNum()); + return (p1p != p2p) ? (p1p > p2p) : (!isFromUs(p1) && isFromUs(p2)); } MeshPacketQueue::MeshPacketQueue(size_t _maxLen) : maxLen(_maxLen) {} diff --git a/src/mesh/MeshTypes.h b/src/mesh/MeshTypes.h index 90cfd5897..27d100fbe 100644 --- a/src/mesh/MeshTypes.h +++ b/src/mesh/MeshTypes.h @@ -50,5 +50,11 @@ extern Allocator &packetPool; */ NodeNum getFrom(const meshtastic_MeshPacket *p); +// Returns true if the packet originated from the local node +bool isFromUs(const meshtastic_MeshPacket *p); + +// Returns true if the packet is destined to us +bool isToUs(const meshtastic_MeshPacket *p); + /* Some clients might not properly set priority, therefore we fix it here. */ void fixPriority(meshtastic_MeshPacket *p); \ No newline at end of file diff --git a/src/mesh/NodeDB.cpp b/src/mesh/NodeDB.cpp index 25314a086..aaf14c5b8 100644 --- a/src/mesh/NodeDB.cpp +++ b/src/mesh/NodeDB.cpp @@ -196,6 +196,18 @@ NodeNum getFrom(const meshtastic_MeshPacket *p) return (p->from == 0) ? nodeDB->getNodeNum() : p->from; } +// Returns true if the packet originated from the local node +bool isFromUs(const meshtastic_MeshPacket *p) +{ + return p->from == 0 || p->from == nodeDB->getNodeNum(); +} + +// Returns true if the packet is destined to us +bool isToUs(const meshtastic_MeshPacket *p) +{ + return p->to == nodeDB->getNodeNum(); +} + bool NodeDB::resetRadioConfig(bool factory_reset) { bool didFactoryReset = false; diff --git a/src/mesh/RadioLibInterface.cpp b/src/mesh/RadioLibInterface.cpp index 807c8aa02..818826018 100644 --- a/src/mesh/RadioLibInterface.cpp +++ b/src/mesh/RadioLibInterface.cpp @@ -186,7 +186,7 @@ ErrorCode RadioLibInterface::send(meshtastic_MeshPacket *p) #ifndef LORA_DISABLE_SENDING printPacket("enqueuing for send", p); - LOG_DEBUG("txGood=%d,rxGood=%d,rxBad=%d\n", txGood, rxGood, rxBad); + LOG_DEBUG("txGood=%d,txRelay=%d,rxGood=%d,rxBad=%d\n", txGood, txRelay, rxGood, rxBad); ErrorCode res = txQueue.enqueue(p) ? ERRNO_OK : ERRNO_UNKNOWN; if (res != ERRNO_OK) { // we weren't able to queue it, so we must drop it to prevent leaks @@ -353,6 +353,8 @@ void RadioLibInterface::completeSending() if (p) { txGood++; + if (!isFromUs(p)) + txRelay++; printPacket("Completed sending", p); // We are done sending that packet, release it diff --git a/src/mesh/RadioLibInterface.h b/src/mesh/RadioLibInterface.h index 090c03046..673f53a32 100644 --- a/src/mesh/RadioLibInterface.h +++ b/src/mesh/RadioLibInterface.h @@ -107,7 +107,7 @@ class RadioLibInterface : public RadioInterface, protected concurrency::Notified /** * Debugging counts */ - uint32_t rxBad = 0, rxGood = 0, txGood = 0; + uint32_t rxBad = 0, rxGood = 0, txGood = 0, txRelay = 0; public: RadioLibInterface(LockingArduinoHal *hal, RADIOLIB_PIN_TYPE cs, RADIOLIB_PIN_TYPE irq, RADIOLIB_PIN_TYPE rst, diff --git a/src/mesh/ReliableRouter.cpp b/src/mesh/ReliableRouter.cpp index 9482f4185..fa05e7973 100644 --- a/src/mesh/ReliableRouter.cpp +++ b/src/mesh/ReliableRouter.cpp @@ -78,7 +78,7 @@ bool ReliableRouter::shouldFilterReceived(const meshtastic_MeshPacket *p) * Resending real ACKs is omitted, as you might receive a packet multiple times due to flooding and * flooding this ACK back to the original sender already adds redundancy. */ bool isRepeated = p->hop_start == 0 ? (p->hop_limit == HOP_RELIABLE) : (p->hop_start == p->hop_limit); - if (wasSeenRecently(p, false) && isRepeated && !MeshModule::currentReply && p->to != nodeDB->getNodeNum()) { + if (wasSeenRecently(p, false) && isRepeated && !MeshModule::currentReply && !isToUs(p)) { LOG_DEBUG("Resending implicit ack for a repeated floodmsg\n"); meshtastic_MeshPacket *tosend = packetPool.allocCopy(*p); tosend->hop_limit--; // bump down the hop count @@ -102,9 +102,7 @@ bool ReliableRouter::shouldFilterReceived(const meshtastic_MeshPacket *p) */ void ReliableRouter::sniffReceived(const meshtastic_MeshPacket *p, const meshtastic_Routing *c) { - NodeNum ourNode = getNodeNum(); - - if (p->to == ourNode) { // ignore ack/nak/want_ack packets that are not address to us (we only handle 0 hop reliability) + if (isToUs(p)) { // ignore ack/nak/want_ack packets that are not address to us (we only handle 0 hop reliability) if (p->want_ack) { if (MeshModule::currentReply) { LOG_DEBUG("Another module replied to this message, no need for 2nd ack\n"); diff --git a/src/mesh/Router.cpp b/src/mesh/Router.cpp index 6ff4364d1..b5732dee9 100644 --- a/src/mesh/Router.cpp +++ b/src/mesh/Router.cpp @@ -169,7 +169,7 @@ ErrorCode Router::sendLocal(meshtastic_MeshPacket *p, RxSource src) LOG_ERROR("Packet received with to: of 0!\n"); } // No need to deliver externally if the destination is the local node - if (p->to == nodeDB->getNodeNum()) { + if (isToUs(p)) { printPacket("Enqueued local", p); enqueueReceivedMessage(p); return ERRNO_OK; @@ -204,7 +204,7 @@ ErrorCode Router::sendLocal(meshtastic_MeshPacket *p, RxSource src) */ ErrorCode Router::send(meshtastic_MeshPacket *p) { - if (p->to == nodeDB->getNodeNum()) { + if (isToUs(p)) { LOG_ERROR("BUG! send() called with packet destined for local node!\n"); packetPool.release(p); return meshtastic_Routing_Error_BAD_REQUEST; @@ -226,7 +226,7 @@ ErrorCode Router::send(meshtastic_MeshPacket *p) service->sendClientNotification(cn); #endif meshtastic_Routing_Error err = meshtastic_Routing_Error_DUTY_CYCLE_LIMIT; - if (getFrom(p) == nodeDB->getNodeNum()) { // only send NAK to API, not to the mesh + if (isFromUs(p)) { // only send NAK to API, not to the mesh abortSendAndNak(err, p); } else { packetPool.release(p); @@ -248,7 +248,7 @@ ErrorCode Router::send(meshtastic_MeshPacket *p) p->from = getFrom(p); // If we are the original transmitter, set the hop limit with which we start - if (p->from == getNodeNum()) + if (isFromUs(p)) p->hop_start = p->hop_limit; // If the packet hasn't yet been encrypted, do so now (it might already be encrypted if we are just forwarding it) @@ -273,7 +273,7 @@ ErrorCode Router::send(meshtastic_MeshPacket *p) } #if !MESHTASTIC_EXCLUDE_MQTT // Only publish to MQTT if we're the original transmitter of the packet - if (moduleConfig.mqtt.enabled && p->from == nodeDB->getNodeNum() && mqtt) { + if (moduleConfig.mqtt.enabled && isFromUs(p) && mqtt) { mqtt->onSend(*p, *p_decoded, chIndex); } #endif @@ -328,9 +328,9 @@ bool perhapsDecode(meshtastic_MeshPacket *p) memcpy(ScratchEncrypted, p->encrypted.bytes, rawSize); #if !(MESHTASTIC_EXCLUDE_PKI) // Attempt PKI decryption first - if (p->channel == 0 && p->to == nodeDB->getNodeNum() && p->to > 0 && p->to != NODENUM_BROADCAST && - nodeDB->getMeshNode(p->from) != nullptr && nodeDB->getMeshNode(p->from)->user.public_key.size > 0 && - nodeDB->getMeshNode(p->to)->user.public_key.size > 0 && rawSize > MESHTASTIC_PKC_OVERHEAD) { + if (p->channel == 0 && isToUs(p) && p->to > 0 && p->to != NODENUM_BROADCAST && nodeDB->getMeshNode(p->from) != nullptr && + nodeDB->getMeshNode(p->from)->user.public_key.size > 0 && nodeDB->getMeshNode(p->to)->user.public_key.size > 0 && + rawSize > MESHTASTIC_PKC_OVERHEAD) { LOG_DEBUG("Attempting PKI decryption\n"); if (crypto->decryptCurve25519(p->from, p->id, rawSize, ScratchEncrypted, bytes)) { @@ -432,7 +432,7 @@ meshtastic_Routing_Error perhapsEncode(meshtastic_MeshPacket *p) // If the packet is not yet encrypted, do so now if (p->which_payload_variant == meshtastic_MeshPacket_decoded_tag) { - if (p->from == nodeDB->getNodeNum()) { + if (isFromUs(p)) { p->decoded.has_bitfield = true; p->decoded.bitfield |= (config.lora.config_ok_to_mqtt << BITFIELD_OK_TO_MQTT_SHIFT); p->decoded.bitfield |= (p->decoded.want_response << BITFIELD_WANT_RESPONSE_SHIFT); @@ -613,7 +613,7 @@ void Router::handleReceived(meshtastic_MeshPacket *p, RxSource src) #if !MESHTASTIC_EXCLUDE_MQTT // After potentially altering it, publish received message to MQTT if we're not the original transmitter of the packet - if (decoded && moduleConfig.mqtt.enabled && getFrom(p) != nodeDB->getNodeNum() && mqtt) + if (decoded && moduleConfig.mqtt.enabled && !isFromUs(p) && mqtt) mqtt->onSend(*p_encrypted, *p, p->channel); #endif } diff --git a/src/mesh/Router.h b/src/mesh/Router.h index fd4b0ccf9..8ebc1a3e5 100644 --- a/src/mesh/Router.h +++ b/src/mesh/Router.h @@ -82,6 +82,10 @@ class Router : protected concurrency::OSThread */ virtual ErrorCode send(meshtastic_MeshPacket *p); + /* Statistics for the amount of duplicate received packets and the amount of times we cancel a relay because someone did it + before us */ + uint32_t rxDupe = 0, txRelayCanceled = 0; + protected: friend class RoutingModule; diff --git a/src/modules/AdminModule.cpp b/src/modules/AdminModule.cpp index b94bbddf2..01ef038e8 100644 --- a/src/modules/AdminModule.cpp +++ b/src/modules/AdminModule.cpp @@ -66,7 +66,7 @@ bool AdminModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshta // if handled == false, then let others look at this message also if they want bool handled = false; assert(r); - bool fromOthers = mp.from != 0 && mp.from != nodeDB->getNodeNum(); + bool fromOthers = !isFromUs(&mp); if (mp.which_payload_variant != meshtastic_MeshPacket_decoded_tag) { return handled; } diff --git a/src/modules/ExternalNotificationModule.cpp b/src/modules/ExternalNotificationModule.cpp index 652db04d3..8abc386ec 100644 --- a/src/modules/ExternalNotificationModule.cpp +++ b/src/modules/ExternalNotificationModule.cpp @@ -428,7 +428,7 @@ ProcessMessage ExternalNotificationModule::handleReceived(const meshtastic_MeshP drv.setWaveform(2, 0); drv.go(); #endif - if (getFrom(&mp) != nodeDB->getNodeNum()) { + if (!isFromUs(&mp)) { // Check if the message contains a bell character. Don't do this loop for every pin, just once. auto &p = mp.decoded; bool containsBell = false; @@ -593,4 +593,4 @@ void ExternalNotificationModule::handleSetRingtone(const char *from_msg) if (changed) { nodeDB->saveProto(rtttlConfigFile, meshtastic_RTTTLConfig_size, &meshtastic_RTTTLConfig_msg, &rtttlConfig); } -} +} \ No newline at end of file diff --git a/src/modules/NodeInfoModule.cpp b/src/modules/NodeInfoModule.cpp index 41f008fb0..61ec375cc 100644 --- a/src/modules/NodeInfoModule.cpp +++ b/src/modules/NodeInfoModule.cpp @@ -26,7 +26,7 @@ bool NodeInfoModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, mes } // if user has changed while packet was not for us, inform phone - if (hasChanged && !wasBroadcast && mp.to != nodeDB->getNodeNum()) + if (hasChanged && !wasBroadcast && !isToUs(&mp)) service->sendToPhone(packetPool.allocCopy(mp)); // LOG_DEBUG("did handleReceived\n"); diff --git a/src/modules/PositionModule.cpp b/src/modules/PositionModule.cpp index f49a654af..6ad30f927 100644 --- a/src/modules/PositionModule.cpp +++ b/src/modules/PositionModule.cpp @@ -54,7 +54,7 @@ bool PositionModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, mes // FIXME this can in fact happen with packets sent from EUD (src=RX_SRC_USER) // to set fixed location, EUD-GPS location or just the time (see also issue #900) bool isLocal = false; - if (nodeDB->getNodeNum() == getFrom(&mp)) { + if (isFromUs(&mp)) { isLocal = true; if (config.position.fixed_position) { LOG_DEBUG("Ignore incoming position update from myself except for time, because position.fixed_position is true\n"); @@ -110,7 +110,7 @@ bool PositionModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, mes void PositionModule::alterReceivedProtobuf(meshtastic_MeshPacket &mp, meshtastic_Position *p) { // Phone position packets need to be truncated to the channel precision - if (nodeDB->getNodeNum() == getFrom(&mp) && (precision < 32 && precision > 0)) { + if (isFromUs(&mp) && (precision < 32 && precision > 0)) { LOG_DEBUG("Truncating phone position to channel precision %i\n", precision); p->latitude_i = p->latitude_i & (UINT32_MAX << (32 - precision)); p->longitude_i = p->longitude_i & (UINT32_MAX << (32 - precision)); diff --git a/src/modules/RangeTestModule.cpp b/src/modules/RangeTestModule.cpp index c98f15d40..e78b4e68d 100644 --- a/src/modules/RangeTestModule.cpp +++ b/src/modules/RangeTestModule.cpp @@ -139,7 +139,7 @@ ProcessMessage RangeTestModuleRadio::handleReceived(const meshtastic_MeshPacket LOG_INFO.getNodeNum(), mp.from, mp.to, mp.id, p.payload.size, p.payload.bytes); */ - if (getFrom(&mp) != nodeDB->getNodeNum()) { + if (!isFromUs(&mp)) { if (moduleConfig.range_test.save) { appendFile(mp); diff --git a/src/modules/RoutingModule.cpp b/src/modules/RoutingModule.cpp index b7be4abc9..3b7be1ab7 100644 --- a/src/modules/RoutingModule.cpp +++ b/src/modules/RoutingModule.cpp @@ -28,7 +28,7 @@ bool RoutingModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, mesh // FIXME - move this to a non promsicious PhoneAPI module? // Note: we are careful not to send back packets that started with the phone back to the phone - if ((mp.to == NODENUM_BROADCAST || mp.to == nodeDB->getNodeNum()) && (mp.from != 0)) { + if ((mp.to == NODENUM_BROADCAST || isToUs(&mp)) && (mp.from != 0)) { printPacket("Delivering rx packet", &mp); service->handleFromRadio(&mp); } diff --git a/src/modules/SerialModule.cpp b/src/modules/SerialModule.cpp index 6d6a947bc..d40b59345 100644 --- a/src/modules/SerialModule.cpp +++ b/src/modules/SerialModule.cpp @@ -310,7 +310,7 @@ ProcessMessage SerialModuleRadio::handleReceived(const meshtastic_MeshPacket &mp // LOG_DEBUG("Received text msg self=0x%0x, from=0x%0x, to=0x%0x, id=%d, msg=%.*s\n", // nodeDB->getNodeNum(), mp.from, mp.to, mp.id, p.payload.size, p.payload.bytes); - if (getFrom(&mp) == nodeDB->getNodeNum()) { + if (!isFromUs(&mp)) { /* * If moduleConfig.serial.echo is true, then echo the packets that are sent out diff --git a/src/modules/StoreForwardModule.cpp b/src/modules/StoreForwardModule.cpp index 58be8c01e..e0092839f 100644 --- a/src/modules/StoreForwardModule.cpp +++ b/src/modules/StoreForwardModule.cpp @@ -333,7 +333,7 @@ void StoreForwardModule::sendErrorTextMessage(NodeNum dest, bool want_response) if (this->busy) { str = "S&F - Busy. Try again shortly."; } else { - str = "S&F - Not available on this channel."; + str = "S&F not permitted on the public channel."; } LOG_WARN("%s\n", str); memcpy(pr->decoded.payload.bytes, str, strlen(str)); @@ -382,8 +382,7 @@ ProcessMessage StoreForwardModule::handleReceived(const meshtastic_MeshPacket &m if ((mp.decoded.portnum == meshtastic_PortNum_TEXT_MESSAGE_APP) && is_server) { auto &p = mp.decoded; - if (mp.to == nodeDB->getNodeNum() && (p.payload.bytes[0] == 'S') && (p.payload.bytes[1] == 'F') && - (p.payload.bytes[2] == 0x00)) { + if (isToUs(&mp) && (p.payload.bytes[0] == 'S') && (p.payload.bytes[1] == 'F') && (p.payload.bytes[2] == 0x00)) { LOG_DEBUG("Legacy Request to send\n"); // Send the last 60 minutes of messages. @@ -396,7 +395,7 @@ ProcessMessage StoreForwardModule::handleReceived(const meshtastic_MeshPacket &m storeForwardModule->historyAdd(mp); LOG_INFO("S&F stored. Message history contains %u records now.\n", this->packetHistoryTotalCount); } - } else if (getFrom(&mp) != nodeDB->getNodeNum() && mp.decoded.portnum == meshtastic_PortNum_STORE_FORWARD_APP) { + } else if (!isFromUs(&mp) && mp.decoded.portnum == meshtastic_PortNum_STORE_FORWARD_APP) { auto &p = mp.decoded; meshtastic_StoreAndForward scratch; meshtastic_StoreAndForward *decoded = NULL; diff --git a/src/modules/Telemetry/DeviceTelemetry.cpp b/src/modules/Telemetry/DeviceTelemetry.cpp index dd5067784..eb3f67e96 100644 --- a/src/modules/Telemetry/DeviceTelemetry.cpp +++ b/src/modules/Telemetry/DeviceTelemetry.cpp @@ -127,6 +127,11 @@ void DeviceTelemetryModule::sendLocalStatsToPhone() telemetry.variant.local_stats.num_packets_tx = RadioLibInterface::instance->txGood; telemetry.variant.local_stats.num_packets_rx = RadioLibInterface::instance->rxGood + RadioLibInterface::instance->rxBad; telemetry.variant.local_stats.num_packets_rx_bad = RadioLibInterface::instance->rxBad; + telemetry.variant.local_stats.num_tx_relay = RadioLibInterface::instance->txRelay; + } + if (router) { + telemetry.variant.local_stats.num_rx_dupe = router->rxDupe; + telemetry.variant.local_stats.num_tx_relay_canceled = router->txRelayCanceled; } LOG_INFO( diff --git a/src/modules/TraceRouteModule.cpp b/src/modules/TraceRouteModule.cpp index be8278824..955098c28 100644 --- a/src/modules/TraceRouteModule.cpp +++ b/src/modules/TraceRouteModule.cpp @@ -16,8 +16,8 @@ void TraceRouteModule::alterReceivedProtobuf(meshtastic_MeshPacket &p, meshtasti // Insert unknown hops if necessary insertUnknownHops(p, r, !incoming.request_id); - // Append ID and SNR. For the last hop (p.to == nodeDB->getNodeNum()), we only need to append the SNR - appendMyIDandSNR(r, p.rx_snr, !incoming.request_id, p.to == nodeDB->getNodeNum()); + // Append ID and SNR. If the last hop is to us, we only need to append the SNR + appendMyIDandSNR(r, p.rx_snr, !incoming.request_id, isToUs(&p)); if (!incoming.request_id) printRoute(r, p.from, p.to, true); else diff --git a/src/modules/esp32/AudioModule.cpp b/src/modules/esp32/AudioModule.cpp index 8a29f9a2e..89e4b4e25 100644 --- a/src/modules/esp32/AudioModule.cpp +++ b/src/modules/esp32/AudioModule.cpp @@ -273,7 +273,7 @@ ProcessMessage AudioModule::handleReceived(const meshtastic_MeshPacket &mp) { if ((moduleConfig.audio.codec2_enabled) && (myRegion->audioPermitted)) { auto &p = mp.decoded; - if (getFrom(&mp) != nodeDB->getNodeNum()) { + if (!isFromUs(&mp)) { memcpy(rx_encode_frame, p.payload.bytes, p.payload.size); radio_state = RadioState::rx; rx_encode_frame_index = p.payload.size; diff --git a/src/mqtt/MQTT.cpp b/src/mqtt/MQTT.cpp index 8d08f97a6..0c1ce0c7c 100644 --- a/src/mqtt/MQTT.cpp +++ b/src/mqtt/MQTT.cpp @@ -150,7 +150,7 @@ void MQTT::onReceive(char *topic, byte *payload, size_t length) // Generate an implicit ACK towards ourselves (handled and processed only locally!) for this message. // We do this because packets are not rebroadcasted back into MQTT anymore and we assume that at least one node // receives it when we get our own packet back. Then we'll stop our retransmissions. - if (e.packet && getFrom(e.packet) == nodeDB->getNodeNum()) + if (e.packet && isFromUs(e.packet)) routingModule->sendAckNak(meshtastic_Routing_Error_NONE, getFrom(e.packet), e.packet->id, ch.index); else LOG_INFO("Ignoring downlink message we originally sent.\n"); @@ -162,7 +162,7 @@ void MQTT::onReceive(char *topic, byte *payload, size_t length) meshtastic_MeshPacket *p = packetPool.allocCopy(*e.packet); p->via_mqtt = true; // Mark that the packet was received via MQTT - if (p->from == 0 || p->from == nodeDB->getNodeNum()) { + if (isFromUs(p)) { LOG_INFO("Ignoring downlink message we originally sent.\n"); packetPool.release(p); return; @@ -188,7 +188,7 @@ void MQTT::onReceive(char *topic, byte *payload, size_t length) const meshtastic_NodeInfoLite *rx = nodeDB->getMeshNode(p->to); // Only accept PKI messages to us, or if we have both the sender and receiver in our nodeDB, as then it's // likely they discovered each other via a channel we have downlink enabled for - if (p->to == nodeDB->getNodeNum() || (tx && tx->has_user && rx && rx->has_user)) + if (isToUs(p) || (tx && tx->has_user && rx && rx->has_user)) router->enqueueReceivedMessage(p); } else if (router && perhapsDecode(p)) // ignore messages if we don't have the channel key router->enqueueReceivedMessage(p); @@ -542,7 +542,7 @@ void MQTT::onSend(const meshtastic_MeshPacket &mp, const meshtastic_MeshPacket & } // check for the lowest bit of the data bitfield set false, and the use of one of the default keys. - if (mp_decoded.from != nodeDB->getNodeNum() && mp_decoded.decoded.has_bitfield && + if (!isFromUs(&mp_decoded) && mp_decoded.decoded.has_bitfield && !(mp_decoded.decoded.bitfield & BITFIELD_OK_TO_MQTT_MASK) && (ch.settings.psk.size < 2 || (ch.settings.psk.size == 16 && memcmp(ch.settings.psk.bytes, defaultpsk, 16)) || (ch.settings.psk.size == 32 && memcmp(ch.settings.psk.bytes, eventpsk, 32)))) { @@ -692,4 +692,4 @@ bool MQTT::isValidJsonEnvelope(JSONObject &json) (json["from"]->AsNumber() == nodeDB->getNodeNum()) && // only accept message if the "from" is us (json.find("type") != json.end()) && json["type"]->IsString() && // should specify a type (json.find("payload") != json.end()); // should have a payload -} +} \ No newline at end of file From e7cfadacd8dbd4f707ab7c09c050d2a9e7d23b51 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Ludovic=20BOU=C3=89?= Date: Fri, 4 Oct 2024 14:47:14 +0200 Subject: [PATCH 52/88] Add Panel_ILI9342 to TFTDisplay.cpp (#4822) * Add Panel_ILI9342 to TFTDisplay.cpp [Panel_ILI9342](https://github.com/lovyan03/LovyanGFX/blob/master/src/lgfx/v1/panel/Panel_ILI9342.hpp) * Add ILI9342_DRIVER to TFTDisplay.cpp * Add ILI9342_DRIVER to Screen.cpp * Add ILI9342_DRIVER to ScreenFonts.h * Add ILI9342_DRIVER to main.cpp * Add ILI9342_DRIVER to images.h * Add ILI9342_DRIVER to NodeDB.cpp * Add ILI9342 to PortduinoGlue.cpp * Add ili9342 to PortduinoGlue.h * Fix formatting * Update Screen.cpp to add ILI9342_DRIVER * Update TFTDisplay.cpp * Update TFTDisplay.cpp * Update Screen.cpp * Update Screen.cpp --------- Co-authored-by: Ben Meadors Co-authored-by: Tom Fifield --- src/graphics/Screen.cpp | 26 ++++++++++++------------ src/graphics/ScreenFonts.h | 6 +++--- src/graphics/TFTDisplay.cpp | 22 ++++++++++++++------ src/graphics/images.h | 4 ++-- src/main.cpp | 6 +++--- src/mesh/NodeDB.cpp | 6 +++--- src/platform/portduino/PortduinoGlue.cpp | 2 ++ src/platform/portduino/PortduinoGlue.h | 2 +- 8 files changed, 43 insertions(+), 31 deletions(-) diff --git a/src/graphics/Screen.cpp b/src/graphics/Screen.cpp index 50350a310..66900c53d 100644 --- a/src/graphics/Screen.cpp +++ b/src/graphics/Screen.cpp @@ -1097,8 +1097,8 @@ static void drawNodes(OLEDDisplay *display, int16_t x, int16_t y, const NodeStat { char usersString[20]; snprintf(usersString, sizeof(usersString), "%d/%d", nodeStatus->getNumOnline(), nodeStatus->getNumTotal()); -#if (defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7701_CS) || defined(ST7735_CS) || defined(ST7789_CS) || \ - defined(USE_ST7789) || defined(HX8357_CS)) && \ +#if (defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ILI9342_DRIVER) || defined(ST7701_CS) || defined(ST7735_CS) || \ + defined(ST7789_CS) || defined(USE_ST7789) || defined(HX8357_CS)) && \ !defined(DISPLAY_FORCE_SMALL_FONTS) display->drawFastImage(x, y + 3, 8, 8, imgUser); #else @@ -1534,8 +1534,8 @@ Screen::Screen(ScanI2C::DeviceAddress address, meshtastic_Config_DisplayConfig_O #elif defined(USE_SSD1306) dispdev = new SSD1306Wire(address.address, -1, -1, geometry, (address.port == ScanI2C::I2CPort::WIRE1) ? HW_I2C::I2C_TWO : HW_I2C::I2C_ONE); -#elif defined(ST7735_CS) || defined(ILI9341_DRIVER) || defined(ST7701_CS) || defined(ST7789_CS) || defined(RAK14014) || \ - defined(HX8357_CS) +#elif defined(ST7735_CS) || defined(ILI9341_DRIVER) || defined(ILI9342_DRIVER) || defined(ST7701_CS) || defined(ST7789_CS) || \ + defined(RAK14014) || defined(HX8357_CS) dispdev = new TFTDisplay(address.address, -1, -1, geometry, (address.port == ScanI2C::I2CPort::WIRE1) ? HW_I2C::I2C_TWO : HW_I2C::I2C_ONE); #elif defined(USE_EINK) && !defined(USE_EINK_DYNAMICDISPLAY) @@ -1732,8 +1732,8 @@ void Screen::setup() // Standard behaviour is to FLIP the screen (needed on T-Beam). If this config item is set, unflip it, and thereby logically // flip it. If you have a headache now, you're welcome. if (!config.display.flip_screen) { -#if defined(ST7701_CS) || defined(ST7735_CS) || defined(ILI9341_DRIVER) || defined(ST7701_CS) || defined(ST7789_CS) || \ - defined(RAK14014) || defined(HX8357_CS) +#if defined(ST7701_CS) || defined(ST7735_CS) || defined(ILI9341_DRIVER) || defined(ILI9342_DRIVER) || defined(ST7701_CS) || \ + defined(ST7789_CS) || defined(RAK14014) || defined(HX8357_CS) static_cast(dispdev)->flipScreenVertically(); #elif defined(USE_ST7789) static_cast(dispdev)->flipScreenVertically(); @@ -2472,8 +2472,8 @@ void DebugInfo::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16 #ifdef ARCH_ESP32 if (!Throttle::isWithinTimespanMs(storeForwardModule->lastHeartbeat, (storeForwardModule->heartbeatInterval * 1200))) { // no heartbeat, overlap a bit -#if (defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7701_CS) || defined(ST7735_CS) || defined(ST7789_CS) || \ - defined(USE_ST7789) || defined(HX8357_CS)) && \ +#if (defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ILI9342_DRIVER) || defined(ST7701_CS) || defined(ST7735_CS) || \ + defined(ST7789_CS) || defined(USE_ST7789) || defined(HX8357_CS) || ARCH_PORTDUINO) && \ !defined(DISPLAY_FORCE_SMALL_FONTS) display->drawFastImage(x + SCREEN_WIDTH - 14 - display->getStringWidth(ourId), y + 3 + FONT_HEIGHT_SMALL, 12, 8, imgQuestionL1); @@ -2484,8 +2484,8 @@ void DebugInfo::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16 imgQuestion); #endif } else { -#if (defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7701_CS) || defined(ST7735_CS) || defined(ST7789_CS) || \ - defined(USE_ST7789) || defined(HX8357_CS)) && \ +#if (defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ILI9342_DRIVER) || defined(ST7701_CS) || defined(ST7735_CS) || \ + defined(ST7789_CS) || defined(USE_ST7789) || defined(HX8357_CS)) && \ !defined(DISPLAY_FORCE_SMALL_FONTS) display->drawFastImage(x + SCREEN_WIDTH - 18 - display->getStringWidth(ourId), y + 3 + FONT_HEIGHT_SMALL, 16, 8, imgSFL1); @@ -2499,8 +2499,8 @@ void DebugInfo::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16 #endif } else { // TODO: Raspberry Pi supports more than just the one screen size -#if (defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7701_CS) || defined(ST7735_CS) || defined(ST7789_CS) || \ - defined(USE_ST7789) || defined(HX8357_CS) || ARCH_PORTDUINO) && \ +#if (defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ILI9342_DRIVER) || defined(ST7701_CS) || defined(ST7735_CS) || \ + defined(ST7789_CS) || defined(USE_ST7789) || defined(HX8357_CS) || ARCH_PORTDUINO) && \ !defined(DISPLAY_FORCE_SMALL_FONTS) display->drawFastImage(x + SCREEN_WIDTH - 14 - display->getStringWidth(ourId), y + 3 + FONT_HEIGHT_SMALL, 12, 8, imgInfoL1); @@ -2817,4 +2817,4 @@ int Screen::handleAdminMessage(const meshtastic_AdminMessage *arg) } // namespace graphics #else graphics::Screen::Screen(ScanI2C::DeviceAddress, meshtastic_Config_DisplayConfig_OledType, OLEDDISPLAY_GEOMETRY) {} -#endif // HAS_SCREEN \ No newline at end of file +#endif // HAS_SCREEN diff --git a/src/graphics/ScreenFonts.h b/src/graphics/ScreenFonts.h index 34c832635..c9ce961fa 100644 --- a/src/graphics/ScreenFonts.h +++ b/src/graphics/ScreenFonts.h @@ -12,8 +12,8 @@ #include "graphics/fonts/OLEDDisplayFontsUA.h" #endif -#if (defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7701_CS) || defined(ST7735_CS) || defined(ST7789_CS) || \ - defined(USE_ST7789) || defined(HX8357_CS)) && \ +#if (defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ILI9342_DRIVER) || defined(ST7701_CS) || defined(ST7735_CS) || \ + defined(ST7789_CS) || defined(USE_ST7789) || defined(HX8357_CS)) && \ !defined(DISPLAY_FORCE_SMALL_FONTS) // The screen is bigger so use bigger fonts #define FONT_SMALL ArialMT_Plain_16 // Height: 19 @@ -41,4 +41,4 @@ #define FONT_HEIGHT_SMALL _fontHeight(FONT_SMALL) #define FONT_HEIGHT_MEDIUM _fontHeight(FONT_MEDIUM) -#define FONT_HEIGHT_LARGE _fontHeight(FONT_LARGE) \ No newline at end of file +#define FONT_HEIGHT_LARGE _fontHeight(FONT_LARGE) diff --git a/src/graphics/TFTDisplay.cpp b/src/graphics/TFTDisplay.cpp index c0326abec..0c32a7c32 100644 --- a/src/graphics/TFTDisplay.cpp +++ b/src/graphics/TFTDisplay.cpp @@ -244,9 +244,9 @@ class LGFX : public lgfx::LGFX_Device static LGFX *tft = nullptr; -#elif defined(ILI9341_DRIVER) +#elif defined(ILI9341_DRIVER) || defined(ILI9342_DRIVER) -#include // Graphics and font library for ILI9341 driver chip +#include // Graphics and font library for ILI9341/ILI9342 driver chip #if defined(ILI9341_BACKLIGHT_EN) && !defined(TFT_BL) #define TFT_BL ILI9341_BACKLIGHT_EN @@ -254,7 +254,11 @@ static LGFX *tft = nullptr; class LGFX : public lgfx::LGFX_Device { +#if defined(ILI9341_DRIVER) lgfx::Panel_ILI9341 _panel_instance; +#elif defined(ILI9342_DRIVER) + lgfx::Panel_ILI9342 _panel_instance; +#endif lgfx::Bus_SPI _bus_instance; lgfx::Light_PWM _light_instance; @@ -265,7 +269,11 @@ class LGFX : public lgfx::LGFX_Device auto cfg = _bus_instance.config(); // configure SPI +#if defined(ILI9341_DRIVER) cfg.spi_host = ILI9341_SPI_HOST; // ESP32-S2,S3,C3 : SPI2_HOST or SPI3_HOST / ESP32 : VSPI_HOST or HSPI_HOST +#elif defined(ILI9342_DRIVER) + cfg.spi_host = ILI9342_SPI_HOST; // ESP32-S2,S3,C3 : SPI2_HOST or SPI3_HOST / ESP32 : VSPI_HOST or HSPI_HOST +#endif cfg.spi_mode = 0; cfg.freq_write = SPI_FREQUENCY; // SPI clock for transmission (up to 80MHz, rounded to the value obtained by dividing // 80MHz by an integer) @@ -336,7 +344,7 @@ class LGFX : public lgfx::LGFX_Device static LGFX *tft = nullptr; #elif defined(ST7735_CS) -#include // Graphics and font library for ILI9341 driver chip +#include // Graphics and font library for ILI9342 driver chip static TFT_eSPI *tft = nullptr; // Invoke library, pins defined in User_Setup.h #elif ARCH_PORTDUINO && HAS_SCREEN != 0 @@ -360,6 +368,8 @@ class LGFX : public lgfx::LGFX_Device _panel_instance = new lgfx::Panel_ST7735S; else if (settingsMap[displayPanel] == ili9341) _panel_instance = new lgfx::Panel_ILI9341; + else if (settingsMap[displayPanel] == ili9342) + _panel_instance = new lgfx::Panel_ILI9342; auto buscfg = _bus_instance.config(); buscfg.spi_mode = 0; buscfg.spi_host = settingsMap[displayspidev]; @@ -618,8 +628,8 @@ static LGFX *tft = nullptr; #endif -#if defined(ST7701_CS) || defined(ST7735_CS) || defined(ST7789_CS) || defined(ILI9341_DRIVER) || defined(RAK14014) || \ - defined(HX8357_CS) || (ARCH_PORTDUINO && HAS_SCREEN != 0) +#if defined(ST7701_CS) || defined(ST7735_CS) || defined(ST7789_CS) || defined(ILI9341_DRIVER) || defined(ILI9342_DRIVER) || \ + defined(RAK14014) || defined(HX8357_CS) || (ARCH_PORTDUINO && HAS_SCREEN != 0) #include "SPILock.h" #include "TFTDisplay.h" #include @@ -850,4 +860,4 @@ bool TFTDisplay::connect() return true; } -#endif \ No newline at end of file +#endif diff --git a/src/graphics/images.h b/src/graphics/images.h index 7028f18e3..2b0854a33 100644 --- a/src/graphics/images.h +++ b/src/graphics/images.h @@ -20,8 +20,8 @@ const uint8_t bluetoothConnectedIcon[36] PROGMEM = {0xfe, 0x01, 0xff, 0x03, 0x03 0xfe, 0x31, 0x00, 0x30, 0x30, 0x30, 0x30, 0x30, 0xf0, 0x3f, 0xe0, 0x1f}; #endif -#if (defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7701_CS) || defined(ST7735_CS) || defined(ST7789_CS) || \ - defined(USE_ST7789) || defined(HX8357_CS) || ARCH_PORTDUINO) && \ +#if (defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ILI9342_DRIVER) || defined(ST7701_CS) || defined(ST7735_CS) || \ + defined(ST7789_CS) || defined(USE_ST7789) || defined(HX8357_CS) || ARCH_PORTDUINO) && \ !defined(DISPLAY_FORCE_SMALL_FONTS) const uint8_t imgQuestionL1[] PROGMEM = {0xff, 0x01, 0x01, 0x32, 0x7b, 0x49, 0x49, 0x6f, 0x26, 0x01, 0x01, 0xff}; const uint8_t imgQuestionL2[] PROGMEM = {0x0f, 0x08, 0x08, 0x08, 0x06, 0x0f, 0x0f, 0x06, 0x08, 0x08, 0x08, 0x0f}; diff --git a/src/main.cpp b/src/main.cpp index a8ea69111..66b843ced 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -773,8 +773,8 @@ void setup() #if !MESHTASTIC_EXCLUDE_I2C // Don't call screen setup until after nodedb is setup (because we need // the current region name) -#if defined(ST7701_CS) || defined(ST7735_CS) || defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7789_CS) || \ - defined(HX8357_CS) || defined(USE_ST7789) +#if defined(ST7701_CS) || defined(ST7735_CS) || defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ILI9342_DRIVER) || \ + defined(ST7789_CS) || defined(HX8357_CS) || defined(USE_ST7789) screen->setup(); #elif defined(ARCH_PORTDUINO) if (screen_found.port != ScanI2C::I2CPort::NO_I2C || settingsMap[displayPanel]) { @@ -1165,4 +1165,4 @@ void loop() mainDelay.delay(delayMsec); } } -#endif \ No newline at end of file +#endif diff --git a/src/mesh/NodeDB.cpp b/src/mesh/NodeDB.cpp index aaf14c5b8..d947f0cea 100644 --- a/src/mesh/NodeDB.cpp +++ b/src/mesh/NodeDB.cpp @@ -358,8 +358,8 @@ void NodeDB::installDefaultConfig(bool preserveKey = false) // FIXME: Default to bluetooth capability of platform as default config.bluetooth.enabled = true; config.bluetooth.fixed_pin = defaultBLEPin; -#if defined(ST7735_CS) || defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ST7789_CS) || defined(HX8357_CS) || \ - defined(USE_ST7789) +#if defined(ST7735_CS) || defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ILI9342_DRIVER) || defined(ST7789_CS) || \ + defined(HX8357_CS) || defined(USE_ST7789) bool hasScreen = true; #elif ARCH_PORTDUINO bool hasScreen = false; @@ -1217,4 +1217,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 +} diff --git a/src/platform/portduino/PortduinoGlue.cpp b/src/platform/portduino/PortduinoGlue.cpp index 44f4d5227..e56016a5b 100644 --- a/src/platform/portduino/PortduinoGlue.cpp +++ b/src/platform/portduino/PortduinoGlue.cpp @@ -223,6 +223,8 @@ void portduinoSetup() settingsMap[displayPanel] = st7796; else if (yamlConfig["Display"]["Panel"].as("") == "ILI9341") settingsMap[displayPanel] = ili9341; + else if (yamlConfig["Display"]["Panel"].as("") == "ILI9342") + settingsMap[displayPanel] = ili9342; else if (yamlConfig["Display"]["Panel"].as("") == "ILI9488") settingsMap[displayPanel] = ili9488; else if (yamlConfig["Display"]["Panel"].as("") == "HX8357D") diff --git a/src/platform/portduino/PortduinoGlue.h b/src/platform/portduino/PortduinoGlue.h index 59956cb59..8ee96717e 100644 --- a/src/platform/portduino/PortduinoGlue.h +++ b/src/platform/portduino/PortduinoGlue.h @@ -57,7 +57,7 @@ enum configNames { maxnodes, ascii_logs }; -enum { no_screen, x11, st7789, st7735, st7735s, st7796, ili9341, ili9488, hx8357d }; +enum { no_screen, x11, st7789, st7735, st7735s, st7796, ili9341, ili9342, ili9488, hx8357d }; enum { no_touchscreen, xpt2046, stmpe610, gt911, ft5x06 }; enum { level_error, level_warn, level_info, level_debug, level_trace }; From 4db0c75c8eda1309ac559dbf9576adfbd8b153b6 Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Fri, 4 Oct 2024 12:06:02 -0500 Subject: [PATCH 53/88] Don't use a static decleration in a header file (#4944) * Don't use a static decleration in a header file * Actually add the rest of the commit --- src/main.cpp | 8 +++++--- userPrefs.h | 6 +++++- 2 files changed, 10 insertions(+), 4 deletions(-) diff --git a/src/main.cpp b/src/main.cpp index 66b843ced..95ac7c1c3 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -120,6 +120,8 @@ float tcxoVoltage = SX126X_DIO3_TCXO_VOLTAGE; // if TCXO is optional, put this h using namespace concurrency; +volatile static const char slipstreamTZString[] = USERPREFS_TZ_STRING; + // We always create a screen object, but we only init it if we find the hardware graphics::Screen *screen = nullptr; @@ -707,15 +709,15 @@ void setup() // setup TZ prior to time actions. #if !MESHTASTIC_EXCLUDE_TZ - LOG_DEBUG("Using compiled/slipstreamed %s\n", USERPREFS_TZ_STRING); // important, removing this clobbers our magic string + LOG_DEBUG("Using compiled/slipstreamed %s\n", slipstreamTZString); // important, removing this clobbers our magic string if (*config.device.tzdef && config.device.tzdef[0] != 0) { LOG_DEBUG("Saved TZ: %s \n", config.device.tzdef); setenv("TZ", config.device.tzdef, 1); } else { - if (strncmp((const char *)USERPREFS_TZ_STRING, "tzpl", 4) == 0) { + if (strncmp((const char *)slipstreamTZString, "tzpl", 4) == 0) { setenv("TZ", "GMT0", 1); } else { - setenv("TZ", (const char *)USERPREFS_TZ_STRING, 1); + setenv("TZ", (const char *)slipstreamTZString, 1); } } tzset(); diff --git a/userPrefs.h b/userPrefs.h index 337bd7976..f544a6535 100644 --- a/userPrefs.h +++ b/userPrefs.h @@ -1,6 +1,10 @@ #ifndef _USERPREFS_ #define _USERPREFS_ -volatile static const char USERPREFS_TZ_STRING[] = "tzplaceholder "; + +// Slipstream values: + +#define USERPREFS_TZ_STRING "tzplaceholder " + // Uncomment and modify to set device defaults // #define USERPREFS_EVENT_MODE 1 From c3b9d493b6d4d131daa68cd7eb4641f9d7eca2cb Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Fri, 4 Oct 2024 15:07:10 -0500 Subject: [PATCH 54/88] Leave the build epoch commented and uncomment when CI runs (#4943) --- .github/actions/setup-base/action.yml | 5 +++++ platformio.ini | 2 +- 2 files changed, 6 insertions(+), 1 deletion(-) diff --git a/.github/actions/setup-base/action.yml b/.github/actions/setup-base/action.yml index 929c1df38..c0f6c4e66 100644 --- a/.github/actions/setup-base/action.yml +++ b/.github/actions/setup-base/action.yml @@ -11,6 +11,11 @@ runs: ref: ${{github.event.pull_request.head.ref}} repository: ${{github.event.pull_request.head.repo.full_name}} + - name: Uncomment build epoch + shell: bash + run: | + sed -i 's/#-DBUILD_EPOCH=$UNIX_TIME/-DBUILD_EPOCH=$UNIX_TIME/' platformio.ini + - name: Install dependencies shell: bash run: | diff --git a/platformio.ini b/platformio.ini index 64d9e7754..22e2b6259 100644 --- a/platformio.ini +++ b/platformio.ini @@ -82,7 +82,7 @@ build_flags = -Wno-missing-field-initializers -DRADIOLIB_EXCLUDE_LORAWAN=1 -DMESHTASTIC_EXCLUDE_DROPZONE=1 -DMESHTASTIC_EXCLUDE_REMOTEHARDWARE=1 - -DBUILD_EPOCH=$UNIX_TIME + #-DBUILD_EPOCH=$UNIX_TIME ;-D OLED_PL monitor_speed = 115200 From 7e946d15ca302aa412d0d637f0314702bf55da0f Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Fri, 4 Oct 2024 22:59:00 -0500 Subject: [PATCH 55/88] Move ifndef to fix test (#4950) --- src/mesh/CryptoEngine.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/mesh/CryptoEngine.cpp b/src/mesh/CryptoEngine.cpp index 5c8fdf6ae..a875eb8b2 100644 --- a/src/mesh/CryptoEngine.cpp +++ b/src/mesh/CryptoEngine.cpp @@ -102,9 +102,9 @@ bool CryptoEngine::decryptCurve25519(uint32_t fromNode, uint64_t packetNum, size uint8_t *auth; // set to last 8 bytes of text? uint32_t extraNonce; // pointer was not really used auth = bytes + numBytes - 12; -#ifndef PIO_UNIT_TESTING memcpy(&extraNonce, auth + 8, sizeof(uint32_t)); // do not use dereference on potential non aligned pointers : (uint32_t *)(auth + 8); +#ifndef PIO_UNIT_TESTING LOG_INFO("Random nonce value: %d\n", extraNonce); meshtastic_NodeInfoLite *node = nodeDB->getMeshNode(fromNode); From e182ae75c261f0315ec4ac2ae7b20534034c7076 Mon Sep 17 00:00:00 2001 From: Tom Fifield Date: Sat, 5 Oct 2024 18:15:20 +0800 Subject: [PATCH 56/88] Remove ancient .gitignore lines (#4952) The files referenced here have not existed for some time. --- .gitignore | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/.gitignore b/.gitignore index 0f2202f8d..28f9a24cc 100644 --- a/.gitignore +++ b/.gitignore @@ -1,6 +1,4 @@ .pio -main/configuration.h -main/credentials.h # ignore vscode IDE settings files .vscode/* @@ -32,4 +30,4 @@ release/ .vscode/extensions.json /compile_commands.json src/mesh/raspihttp/certificate.pem -src/mesh/raspihttp/private_key.pem \ No newline at end of file +src/mesh/raspihttp/private_key.pem From 55049ed547103787d700e0df5331f88755b89d8d Mon Sep 17 00:00:00 2001 From: Tom Fifield Date: Sat, 5 Oct 2024 18:24:12 +0800 Subject: [PATCH 57/88] Remove unused Jlink monitoring files (#4953) The NRF52 JLINK_MONITOR are unmodified copies of code from Nordic (https://github.com/NordicPlayground/j-link-monitoring-mode-debugging ), which are not used by our firmware and have not been touched in ~4 years. --- src/platform/nrf52/JLINK_MONITOR.c | 124 --- src/platform/nrf52/JLINK_MONITOR.h | 27 - src/platform/nrf52/JLINK_MONITOR_ISR_SES.S | 888 --------------------- 3 files changed, 1039 deletions(-) delete mode 100644 src/platform/nrf52/JLINK_MONITOR.c delete mode 100644 src/platform/nrf52/JLINK_MONITOR.h delete mode 100644 src/platform/nrf52/JLINK_MONITOR_ISR_SES.S diff --git a/src/platform/nrf52/JLINK_MONITOR.c b/src/platform/nrf52/JLINK_MONITOR.c deleted file mode 100644 index 160264905..000000000 --- a/src/platform/nrf52/JLINK_MONITOR.c +++ /dev/null @@ -1,124 +0,0 @@ -/********************************************************************* -* SEGGER Microcontroller GmbH & Co. KG * -* The Embedded Experts * -********************************************************************** -* * -* (c) 1995 - 2015 SEGGER Microcontroller GmbH & Co. KG * -* * -* www.segger.com Support: support@segger.com * -* * -********************************************************************** - ----------------------------------------------------------------------- -File : JLINK_MONITOR.c -Purpose : Implementation of debug monitor for J-Link monitor mode debug on Cortex-M devices. --------- END-OF-HEADER --------------------------------------------- -*/ - -#include "JLINK_MONITOR.h" - -/********************************************************************* - * - * Configuration - * - ********************************************************************** - */ - -/********************************************************************* - * - * Defines - * - ********************************************************************** - */ - -/********************************************************************* - * - * Types - * - ********************************************************************** - */ - -/********************************************************************* - * - * Static data - * - ********************************************************************** - */ - -volatile int MAIN_MonCnt; // Incremented in JLINK_MONITOR_OnPoll() while CPU is in debug mode - -/********************************************************************* - * - * Local functions - * - ********************************************************************** - */ - -/********************************************************************* - * - * Global functions - * - ********************************************************************** - */ - -/********************************************************************* - * - * JLINK_MONITOR_OnExit() - * - * Function description - * Called from DebugMon_Handler(), once per debug exit. - * May perform some target specific operations to be done on debug mode exit. - * - * Notes - * (1) Must not keep the CPU busy for more than 100 ms - */ -void JLINK_MONITOR_OnExit(void) -{ - // - // Add custom code here - // - // BSP_ClrLED(0); -} - -/********************************************************************* - * - * JLINK_MONITOR_OnEnter() - * - * Function description - * Called from DebugMon_Handler(), once per debug entry. - * May perform some target specific operations to be done on debug mode entry - * - * Notes - * (1) Must not keep the CPU busy for more than 100 ms - */ -void JLINK_MONITOR_OnEnter(void) -{ - // - // Add custom code here - // - // BSP_SetLED(0); - // BSP_ClrLED(1); -} - -/********************************************************************* - * - * JLINK_MONITOR_OnPoll() - * - * Function description - * Called periodically from DebugMon_Handler(), to perform some actions that need to be performed periodically during debug - * mode. - * - * Notes - * (1) Must not keep the CPU busy for more than 100 ms - */ -void JLINK_MONITOR_OnPoll(void) -{ - // - // Add custom code here - // - MAIN_MonCnt++; - // BSP_ToggleLED(0); - // _Delay(500000); -} - -/****** End Of File *************************************************/ diff --git a/src/platform/nrf52/JLINK_MONITOR.h b/src/platform/nrf52/JLINK_MONITOR.h deleted file mode 100644 index 87cf332fe..000000000 --- a/src/platform/nrf52/JLINK_MONITOR.h +++ /dev/null @@ -1,27 +0,0 @@ -/********************************************************************* -* SEGGER Microcontroller GmbH & Co. KG * -* The Embedded Experts * -********************************************************************** -* * -* (c) 1995 - 2015 SEGGER Microcontroller GmbH & Co. KG * -* * -* www.segger.com Support: support@segger.com * -* * -********************************************************************** - ----------------------------------------------------------------------- -File : JLINK_MONITOR.h -Purpose : Header file of debug monitor for J-Link monitor mode debug on Cortex-M devices. --------- END-OF-HEADER --------------------------------------------- -*/ - -#ifndef JLINK_MONITOR_H -#define JLINK_MONITOR_H - -void JLINK_MONITOR_OnExit(void); -void JLINK_MONITOR_OnEnter(void); -void JLINK_MONITOR_OnPoll(void); - -#endif - -/****** End Of File *************************************************/ diff --git a/src/platform/nrf52/JLINK_MONITOR_ISR_SES.S b/src/platform/nrf52/JLINK_MONITOR_ISR_SES.S deleted file mode 100644 index cda4b1a50..000000000 --- a/src/platform/nrf52/JLINK_MONITOR_ISR_SES.S +++ /dev/null @@ -1,888 +0,0 @@ -/********************************************************************* -* SEGGER Microcontroller GmbH & Co. KG * -* The Embedded Experts * -********************************************************************** -* * -* (c) 1995 - 2015 SEGGER Microcontroller GmbH & Co. KG * -* * -* www.segger.com Support: support@segger.com * -* * -********************************************************************** - ----------------------------------------------------------------------- -File : JLINK_MONITOR_ISR_SES.s -Purpose : Implementation of debug monitor for J-Link monitor mode - debug on Cortex-M devices, supporting SES compiler. --------- END-OF-HEADER --------------------------------------------- -*/ - - .name JLINK_MONITOR_ISR - .syntax unified - - .extern JLINK_MONITOR_OnEnter - .extern JLINK_MONITOR_OnExit - .extern JLINK_MONITOR_OnPoll - - .global DebugMon_Handler - -/********************************************************************* -* -* Defines, configurable -* -********************************************************************** -*/ - -#define _MON_VERSION 100 // V x.yy - -/********************************************************************* -* -* Defines, fixed -* -********************************************************************** -*/ - -#define _APP_SP_OFF_R0 0x00 -#define _APP_SP_OFF_R1 0x04 -#define _APP_SP_OFF_R2 0x08 -#define _APP_SP_OFF_R3 0x0C -#define _APP_SP_OFF_R12 0x10 -#define _APP_SP_OFF_R14_LR 0x14 -#define _APP_SP_OFF_PC 0x18 -#define _APP_SP_OFF_XPSR 0x1C -#define _APP_SP_OFF_S0 0x20 -#define _APP_SP_OFF_S1 0x24 -#define _APP_SP_OFF_S2 0x28 -#define _APP_SP_OFF_S3 0x2C -#define _APP_SP_OFF_S4 0x30 -#define _APP_SP_OFF_S5 0x34 -#define _APP_SP_OFF_S6 0x38 -#define _APP_SP_OFF_S7 0x3C -#define _APP_SP_OFF_S8 0x40 -#define _APP_SP_OFF_S9 0x44 -#define _APP_SP_OFF_S10 0x48 -#define _APP_SP_OFF_S11 0x4C -#define _APP_SP_OFF_S12 0x50 -#define _APP_SP_OFF_S13 0x54 -#define _APP_SP_OFF_S14 0x58 -#define _APP_SP_OFF_S15 0x5C -#define _APP_SP_OFF_FPSCR 0x60 - -#define _NUM_BYTES_BASIC_STACKFRAME 32 -#define _NUM_BYTES_EXTENDED_STACKFRAME 72 - -#define _SYSTEM_DCRDR_OFF 0x00 -#define _SYSTEM_DEMCR_OFF 0x04 - -#define _SYSTEM_DHCSR 0xE000EDF0 // Debug Halting Control and Status Register (DHCSR) -#define _SYSTEM_DCRSR 0xE000EDF4 // Debug Core Register Selector Register (DCRSR) -#define _SYSTEM_DCRDR 0xE000EDF8 // Debug Core Register Data Register (DCRDR) -#define _SYSTEM_DEMCR 0xE000EDFC // Debug Exception and Monitor Control Register (DEMCR) - -#define _SYSTEM_FPCCR 0xE000EF34 // Floating-Point Context Control Register (FPCCR) -#define _SYSTEM_FPCAR 0xE000EF38 // Floating-Point Context Address Register (FPCAR) -#define _SYSTEM_FPDSCR 0xE000EF3C // Floating-Point Default Status Control Register (FPDSCR) -#define _SYSTEM_MVFR0 0xE000EF40 // Media and FP Feature Register 0 (MVFR0) -#define _SYSTEM_MVFR1 0xE000EF44 // Media and FP Feature Register 1 (MVFR1) - -/* -* Defines for determining if the current debug config supports FPU registers -* For some compilers like IAR EWARM when disabling the FPU in the compiler settings an error is thrown when -*/ -#ifdef __FPU_PRESENT - #if __FPU_PRESENT - #define _HAS_FPU_REGS 1 - #else - #define _HAS_FPU_REGS 0 - #endif -#else - #define _HAS_FPU_REGS 0 -#endif - -/********************************************************************* -* -* Signature of monitor -* -* Function description -* Needed for targets where also a boot ROM is present that possibly specifies a vector table with a valid debug monitor exception entry -*/ - .section .text, "ax" - - // - // JLINKMONHANDLER - // - .byte 0x4A - .byte 0x4C - .byte 0x49 - .byte 0x4E - .byte 0x4B - .byte 0x4D - .byte 0x4F - .byte 0x4E - .byte 0x48 - .byte 0x41 - .byte 0x4E - .byte 0x44 - .byte 0x4C - .byte 0x45 - .byte 0x52 - .byte 0x00 // Align to 8-bytes - -/********************************************************************* -* -* DebugMon_Handler() -* -* Function description -* Debug monitor handler. CPU enters this handler in case a "halt" request is made from the debugger. -* This handler is also responsible for handling commands that are sent by the debugger. -* -* Notes -* This is actually the ISR for the debug interrupt (exception no. 12) -*/ - .thumb_func - -DebugMon_Handler: - /* - General procedure: - DCRDR is used as communication register - DEMCR[19] is used as ready flag - For the command J-Link sends to the monitor: DCRDR[7:0] == Cmd, DCRDR[31:8] == ParamData - - 1) Monitor sets DEMCR[19] whenever it is ready to receive new commands/data - DEMCR[19] is initially set on debug monitor entry - 2) J-Link will clear once it has placed conmmand/data in DCRDR for J-Link - 3) Monitor will wait for DEMCR[19] to be cleared - 4) Monitor will process command (May cause additional data transfers etc., depends on command - 5) No restart-CPU command? => Back to 2), Otherwise => 6) - 6) Monitor will clear DEMCR[19] 19 to indicate that it is no longer ready - */ - PUSH {LR} - BL JLINK_MONITOR_OnEnter - POP {LR} - LDR.N R3,_AddrDCRDR // 0xe000edf8 == _SYSTEM_DCRDR - B.N _IndicateMonReady -_WaitProbeReadIndicateMonRdy: // while(_SYSTEM_DEMCR & (1uL << 19)); => Wait until J-Link has read item - LDR R0,[R3, #+_SYSTEM_DEMCR_OFF] // _SYSTEM_DEMCR - LSLS R0,R0,#+12 - BMI.N _WaitProbeReadIndicateMonRdy -_IndicateMonReady: - LDR R0,[R3, #+_SYSTEM_DEMCR_OFF] // _SYSTEM_DEMCR |= (1uL << 19); => Set MON_REQ bit, so J-Link knows monitor is ready to receive commands - ORR R0,R0,#0x80000 - STR R0,[R3, #+_SYSTEM_DEMCR_OFF] - /* - During command loop: - R0 = Tmp - R1 = Tmp - R2 = Tmp - R3 = &_SYSTEM_DCRDR (allows also access to DEMCR with offset) - R12 = Tmp - - Outside command loop R0-R3 and R12 may be overwritten by MONITOR_OnPoll() - */ -_WaitForJLinkCmd: // do { - PUSH {LR} - BL JLINK_MONITOR_OnPoll - POP {LR} - LDR.N R3,_AddrDCRDR // 0xe000edf8 == _SYSTEM_DCRDR - LDR R0,[R3, #+_SYSTEM_DEMCR_OFF] - LSRS R0,R0,#+20 // DEMCR[19] -> Carry Clear? => J-Link has placed command for us - BCS _WaitForJLinkCmd - /* - Perform command - Command is placed by J-Link in DCRDR[7:0] and additional parameter data is stored in DCRDR[31:8] - J-Link clears DEMCR[19] to indicate that it placed a command/data or read data - Monitor sets DEMCR[19] to indicate that it placed data or read data / is ready for a new command - Setting DEMCR[19] indicates "monitor ready for new command / data" and also indicates: "data has been placed in DCRDR by monitor, for J-Link" - Therefore it is responsibility of the commands to respond to the commands accordingly - - Commands for debug monitor - Commands must not exceed 0xFF (255) as we only defined 8-bits for command-part. Higher 24-bits are parameter info for current command - - Protocol for different commands: - J-Link: Cmd -> DCRDR, DEMCR[19] -> 0 => Cmd placed by probe - */ - LDR R0,[R3, #+_SYSTEM_DCRDR_OFF] // ParamInfo = _SYSTEM_DCRDR - LSRS R1,R0,#+8 // ParamInfo >>= 8 - LSLS R0,R0,#+24 - LSRS R0,R0,#+24 // Cmd = ParamInfo & 0xFF - // - // switch (Cmd) - // - CMP R0,#+0 - BEQ.N _HandleGetMonVersion // case _MON_CMD_GET_MONITOR_VERSION - CMP R0,#+2 - BEQ.N _HandleReadReg // case _MON_CMD_READ_REG - BCC.N _HandleRestartCPU // case _MON_CMD_RESTART_CPU - CMP R0,#+3 - BEQ.N _HandleWriteReg_Veneer // case _MON_CMD_WRITE_REG - B.N _IndicateMonReady // default : while (1); - /* - Return - _MON_CMD_RESTART_CPU - CPU: DEMCR[19] -> 0 => Monitor no longer ready - */ -_HandleRestartCPU: - LDR R0,[R3, #+_SYSTEM_DEMCR_OFF] // _SYSTEM_DEMCR &= ~(1uL << 19); => Clear MON_REQ to indicate that monitor is no longer active - BIC R0,R0,#0x80000 - STR R0,[R3, #+_SYSTEM_DEMCR_OFF] - PUSH {LR} - BL JLINK_MONITOR_OnExit - POP {PC} - // - // Place data section here to not get in trouble with load-offsets - // - .section .text, "ax", %progbits - .align 2 -_AddrDCRDR: - .long 0xE000EDF8 -_AddrCPACR: - .long 0xE000ED88 - - .section .text, "ax" - .thumb_func - -;/********************************************************************* -;* -;* _HandleGetMonVersion -;* -;*/ -_HandleGetMonVersion: - /* - _MON_CMD_GET_MONITOR_VERSION - CPU: Data -> DCRDR, DEMCR[19] -> 1 => Data ready - J-Link: DCRDR -> Read, DEMCR[19] -> 0 => Data read - CPU: DEMCR[19] -> 1 => Mon ready - */ - MOVS R0,#+_MON_VERSION - STR R0,[R3, #+_SYSTEM_DCRDR_OFF] // _SYSTEM_DCRDR = x - LDR R0,[R3, #+_SYSTEM_DEMCR_OFF] // _SYSTEM_DEMCR |= (1uL << 19); => Set MON_REQ bit, so J-Link knows monitor is ready to receive commands - ORR R0,R0,#0x80000 - STR R0,[R3, #+_SYSTEM_DEMCR_OFF] // Indicate data ready - B _WaitProbeReadIndicateMonRdy - -/********************************************************************* -* -* _HandleReadReg -* -*/ -_HandleWriteReg_Veneer: - B.N _HandleWriteReg -_HandleReadReg: - /* - _MON_CMD_READ_REG - CPU: Data -> DCRDR, DEMCR[19] -> 1 => Data ready - J-Link: DCRDR -> Read, DEMCR[19] -> 0 => Data read - CPU: DEMCR[19] -> 1 => Mon ready - - - Register indexes - 0-15: R0-R15 (13 == R13 reserved => is banked ... Has to be read as PSP / MSP. Decision has to be done by J-Link DLL side!) - 16: XPSR - 17: MSP - 18: PSP - 19: CFBP CONTROL/FAULTMASK/BASEPRI/PRIMASK (packed into 4 bytes of word. CONTROL = CFBP[31:24], FAULTMASK = CFBP[16:23], BASEPRI = CFBP[15:8], PRIMASK = CFBP[7:0] - 20: FPSCR - 21-52: FPS0-FPS31 - - - Register usage when entering this "subroutine": - R0 Cmd - R1 ParamInfo - R2 --- - R3 = &_SYSTEM_DCRDR (allows also access to DEMCR with offset) - R12 --- - - Table B1-9 EXC_RETURN definition of exception return behavior, with FP extension - LR Return to Return SP Frame type - --------------------------------------------------------- - 0xFFFFFFE1 Handler mode. MSP Extended - 0xFFFFFFE9 Thread mode MSP Extended - 0xFFFFFFED Thread mode PSP Extended - 0xFFFFFFF1 Handler mode. MSP Basic - 0xFFFFFFF9 Thread mode MSP Basic - 0xFFFFFFFD Thread mode PSP Basic - - So LR[2] == 1 => Return stack == PSP else MSP - - R0-R3, R12, PC, xPSR can be read from application stackpointer - Other regs can be read directly - */ - LSRS R2,LR,#+3 // Shift LR[2] into carry => Carry clear means that CPU was running on MSP - ITE CS - MRSCS R2,PSP - MRSCC R2,MSP - CMP R1,#+4 // if (RegIndex < 4) { (R0-R3) - BCS _HandleReadRegR4 - LDR R0,[R2, R1, LSL #+2] // v = [SP + Rx * 4] (R0-R3) - B.N _HandleReadRegDone -_HandleReadRegR4: - CMP R1,#+5 // if (RegIndex < 5) { (R4) - BCS _HandleReadRegR5 - MOV R0,R4 - B.N _HandleReadRegDone -_HandleReadRegR5: - CMP R1,#+6 // if (RegIndex < 6) { (R5) - BCS _HandleReadRegR6 - MOV R0,R5 - B.N _HandleReadRegDone -_HandleReadRegR6: - CMP R1,#+7 // if (RegIndex < 7) { (R6) - BCS _HandleReadRegR7 - MOV R0,R6 - B.N _HandleReadRegDone -_HandleReadRegR7: - CMP R1,#+8 // if (RegIndex < 8) { (R7) - BCS _HandleReadRegR8 - MOV R0,R7 - B.N _HandleReadRegDone -_HandleReadRegR8: - CMP R1,#+9 // if (RegIndex < 9) { (R8) - BCS _HandleReadRegR9 - MOV R0,R8 - B.N _HandleReadRegDone -_HandleReadRegR9: - CMP R1,#+10 // if (RegIndex < 10) { (R9) - BCS _HandleReadRegR10 - MOV R0,R9 - B.N _HandleReadRegDone -_HandleReadRegR10: - CMP R1,#+11 // if (RegIndex < 11) { (R10) - BCS _HandleReadRegR11 - MOV R0,R10 - B.N _HandleReadRegDone -_HandleReadRegR11: - CMP R1,#+12 // if (RegIndex < 12) { (R11) - BCS _HandleReadRegR12 - MOV R0,R11 - B.N _HandleReadRegDone -_HandleReadRegR12: - CMP R1,#+14 // if (RegIndex < 14) { (R12) - BCS _HandleReadRegR14 - LDR R0,[R2, #+_APP_SP_OFF_R12] - B.N _HandleReadRegDone -_HandleReadRegR14: - CMP R1,#+15 // if (RegIndex < 15) { (R14 / LR) - BCS _HandleReadRegR15 - LDR R0,[R2, #+_APP_SP_OFF_R14_LR] - B.N _HandleReadRegDone -_HandleReadRegR15: - CMP R1,#+16 // if (RegIndex < 16) { (R15 / PC) - BCS _HandleReadRegXPSR - LDR R0,[R2, #+_APP_SP_OFF_PC] - B.N _HandleReadRegDone -_HandleReadRegXPSR: - CMP R1,#+17 // if (RegIndex < 17) { (xPSR) - BCS _HandleReadRegMSP - LDR R0,[R2, #+_APP_SP_OFF_XPSR] - B.N _HandleReadRegDone -_HandleReadRegMSP: - /* - Stackpointer is tricky because we need to get some info about the SP used in the user app, first - - Handle reading R0-R3 which can be read right from application stackpointer - - Table B1-9 EXC_RETURN definition of exception return behavior, with FP extension - LR Return to Return SP Frame type - --------------------------------------------------------- - 0xFFFFFFE1 Handler mode. MSP Extended - 0xFFFFFFE9 Thread mode MSP Extended - 0xFFFFFFED Thread mode PSP Extended - 0xFFFFFFF1 Handler mode. MSP Basic - 0xFFFFFFF9 Thread mode MSP Basic - 0xFFFFFFFD Thread mode PSP Basic - - So LR[2] == 1 => Return stack == PSP else MSP - Per architecture definition: Inside monitor (exception) SP = MSP - - Stack pointer handling is complicated because it is different what is pushed on the stack before entering the monitor ISR... - Cortex-M: 8 regs - Cortex-M + forced-stack-alignment: 8 regs + 1 dummy-word if stack was not 8-byte aligned - Cortex-M + FPU: 8 regs + 17 FPU regs + 1 dummy-word + 1-dummy word if stack was not 8-byte aligned - Cortex-M + FPU + lazy mode: 8 regs + 17 dummy-words + 1 dummy-word + 1-dummy word if stack was not 8-byte aligned - */ - CMP R1,#+18 // if (RegIndex < 18) { (MSP) - BCS _HandleReadRegPSP - MRS R0,MSP - LSRS R1,LR,#+3 // LR[2] -> Carry == 0 => CPU was running on MSP => Needs correction - BCS _HandleReadRegDone_Veneer // CPU was running on PSP? => No correction necessary -_HandleSPCorrection: - LSRS R1,LR,#+5 // LR[4] -> Carry == 0 => extended stack frame has been allocated. See ARM DDI0403D, B1.5.7 Stack alignment on exception entry - ITE CS - ADDCS R0,R0,#+_NUM_BYTES_BASIC_STACKFRAME - ADDCC R0,R0,#+_NUM_BYTES_EXTENDED_STACKFRAME - LDR R1,[R2, #+_APP_SP_OFF_XPSR] // Get xPSR from application stack (R2 has been set to app stack on beginning of _HandleReadReg) - LSRS R1,R1,#+5 // xPSR[9] -> Carry == 1 => Stack has been force-aligned before pushing regs. See ARM DDI0403D, B1.5.7 Stack alignment on exception entry - IT CS - ADDCS R0,R0,#+4 - B _HandleReadRegDone -_HandleReadRegPSP: // RegIndex == 18 - CMP R1,#+19 // if (RegIndex < 19) { - BCS _HandleReadRegCFBP - MRS R0,PSP // PSP is not touched by monitor - LSRS R1,LR,#+3 // LR[2] -> Carry == 1 => CPU was running on PSP => Needs correction - BCC _HandleReadRegDone_Veneer // CPU was running on MSP? => No correction of PSP necessary - B _HandleSPCorrection -_HandleReadRegCFBP: - /* - CFBP is a register that can only be read via debug probe and is a merger of the following regs: - CONTROL/FAULTMASK/BASEPRI/PRIMASK (packed into 4 bytes of word. CONTROL = CFBP[31:24], FAULTMASK = CFBP[16:23], BASEPRI = CFBP[15:8], PRIMASK = CFBP[7:0] - To keep J-Link side the same for monitor and halt mode, we also return CFBP in monitor mode - */ - CMP R1,#+20 // if (RegIndex < 20) { (CFBP) - BCS _HandleReadRegFPU - MOVS R0,#+0 - MRS R2,PRIMASK - ORRS R0,R2 // Merge PRIMASK into CFBP[7:0] - MRS R2,BASEPRI - LSLS R2,R2,#+8 // Merge BASEPRI into CFBP[15:8] - ORRS R0,R2 - MRS R2,FAULTMASK - LSLS R2,R2,#+16 // Merge FAULTMASK into CFBP[23:16] - ORRS R0,R2 - MRS R2,CONTROL - LSRS R1,LR,#3 // LR[2] -> Carry. CONTROL.SPSEL is saved to LR[2] on exception entry => ARM DDI0403D, B1.5.6 Exception entry behavior - IT CS // As J-Link sees value of CONTROL at application time, we need reconstruct original value of CONTROL - ORRCS R2,R2,#+2 // CONTROL.SPSEL (CONTROL[1]) == 0 inside monitor - LSRS R1,LR,#+5 // LR[4] == NOT(CONTROL.FPCA) -> Carry - ITE CS // Merge original value of FPCA (CONTROL[2]) into read data - BICCS R2,R2,#+0x04 // Remember LR contains NOT(CONTROL) - ORRCC R2,R2,#+0x04 - LSLS R2,R2,#+24 - ORRS R0,R2 - B.N _HandleReadRegDone -_HandleReadRegFPU: -#if _HAS_FPU_REGS - CMP R1,#+53 // if (RegIndex < 53) { (20 (FPSCR), 21-52 FPS0-FPS31) - BCS _HandleReadRegDone_Veneer - /* - Read Coprocessor Access Control Register (CPACR) to check if CP10 and CP11 are enabled - If not, access to floating point is not possible - CPACR[21:20] == CP10 enable. 0b01 = Privileged access only. 0b11 = Full access. Other = reserved - CPACR[23:22] == CP11 enable. 0b01 = Privileged access only. 0b11 = Full access. Other = reserved - */ - LDR R0,_AddrCPACR - LDR R0,[R0] - LSLS R0,R0,#+8 - LSRS R0,R0,#+28 - CMP R0,#+0xF - BEQ _HandleReadRegFPU_Allowed - CMP R0,#+0x5 - BNE _HandleReadRegDone_Veneer -_HandleReadRegFPU_Allowed: - CMP R1,#+21 // if (RegIndex < 21) (20 == FPSCR) - BCS _HandleReadRegFPS0_FPS31 - LSRS R0,LR,#+5 // CONTROL[2] == FPCA => NOT(FPCA) saved to LR[4]. LR[4] == 0 => Extended stack frame, so FPU regs possibly on stack - BCS _HandleReadFPSCRLazyMode // Remember: NOT(FPCA) is stored to LR. == 0 means: Extended stack frame - LDR R0,=_SYSTEM_FPCCR - LDR R0,[R0] - LSLS R0,R0,#+2 // FPCCR[30] -> Carry == 1 indicates if lazy mode is active, so space on stack is reserved but FPU registers are not saved on stack - BCS _HandleReadFPSCRLazyMode - LDR R0,[R2, #+_APP_SP_OFF_FPSCR] - B _HandleReadRegDone -_HandleReadFPSCRLazyMode: - VMRS R0,FPSCR - B _HandleReadRegDone -_HandleReadRegFPS0_FPS31: // RegIndex == 21-52 - LSRS R0,LR,#+5 // CONTROL[2] == FPCA => NOT(FPCA) saved to LR[4]. LR[4] == 0 => Extended stack frame, so FPU regs possibly on stack - BCS _HandleReadFPS0_FPS31LazyMode // Remember: NOT(FPCA) is stored to LR. == 0 means: Extended stack frame - LDR R0,=_SYSTEM_FPCCR - LDR R0,[R0] - LSLS R0,R0,#+2 // FPCCR[30] -> Carry == 1 indicates if lazy mode is active, so space on stack is reserved but FPU registers are not saved on stack - BCS _HandleReadFPS0_FPS31LazyMode - SUBS R1,#+21 // Convert absolute reg index into rel. one - LSLS R1,R1,#+2 // RegIndex to position on stack - ADDS R1,#+_APP_SP_OFF_S0 - LDR R0,[R2, R1] -_HandleReadRegDone_Veneer: - B _HandleReadRegDone -_HandleReadFPS0_FPS31LazyMode: - SUBS R1,#+20 // convert abs. RegIndex into rel. one - MOVS R0,#+6 - MULS R1,R0,R1 - LDR R0,=_HandleReadRegUnknown - SUB R0,R0,R1 // _HandleReadRegUnknown - 6 * ((RegIndex - 21) + 1) - ORR R0,R0,#1 // Thumb bit needs to be set in DestAddr - BX R0 - // - // Table for reading FPS0-FPS31 - // - VMOV R0,S31 // v = FPSx - B _HandleReadRegDone - VMOV R0,S30 - B _HandleReadRegDone - VMOV R0,S29 - B _HandleReadRegDone - VMOV R0,S28 - B _HandleReadRegDone - VMOV R0,S27 - B _HandleReadRegDone - VMOV R0,S26 - B _HandleReadRegDone - VMOV R0,S25 - B _HandleReadRegDone - VMOV R0,S24 - B _HandleReadRegDone - VMOV R0,S23 - B _HandleReadRegDone - VMOV R0,S22 - B _HandleReadRegDone - VMOV R0,S21 - B _HandleReadRegDone - VMOV R0,S20 - B _HandleReadRegDone - VMOV R0,S19 - B _HandleReadRegDone - VMOV R0,S18 - B _HandleReadRegDone - VMOV R0,S17 - B _HandleReadRegDone - VMOV R0,S16 - B _HandleReadRegDone - VMOV R0,S15 - B _HandleReadRegDone - VMOV R0,S14 - B _HandleReadRegDone - VMOV R0,S13 - B _HandleReadRegDone - VMOV R0,S12 - B _HandleReadRegDone - VMOV R0,S11 - B _HandleReadRegDone - VMOV R0,S10 - B _HandleReadRegDone - VMOV R0,S9 - B _HandleReadRegDone - VMOV R0,S8 - B _HandleReadRegDone - VMOV R0,S7 - B _HandleReadRegDone - VMOV R0,S6 - B _HandleReadRegDone - VMOV R0,S5 - B _HandleReadRegDone - VMOV R0,S4 - B _HandleReadRegDone - VMOV R0,S3 - B _HandleReadRegDone - VMOV R0,S2 - B _HandleReadRegDone - VMOV R0,S1 - B _HandleReadRegDone - VMOV R0,S0 - B _HandleReadRegDone -#else - B _HandleReadRegUnknown -_HandleReadRegDone_Veneer: - B _HandleReadRegDone -#endif -_HandleReadRegUnknown: - MOVS R0,#+0 // v = 0 - B.N _HandleReadRegDone -_HandleReadRegDone: - - // Send register content to J-Link and wait until J-Link has read the data - - STR R0,[R3, #+_SYSTEM_DCRDR_OFF] // DCRDR = v; - LDR R0,[R3, #+_SYSTEM_DEMCR_OFF] // _SYSTEM_DEMCR |= (1uL << 19); => Set MON_REQ bit, so J-Link knows monitor is ready to receive commands - ORR R0,R0,#0x80000 - STR R0,[R3, #+_SYSTEM_DEMCR_OFF] // Indicate data ready - B _WaitProbeReadIndicateMonRdy - - // Data section for register addresses - -_HandleWriteReg: - /* - _MON_CMD_WRITE_REG - CPU: DEMCR[19] -> 1 => Mon ready - J-Link: Data -> DCRDR, DEMCR[19] -> 0 => Data placed by probe - CPU: DCRDR -> Read, Process command, DEMCR[19] -> 1 => Data read & mon ready - - Register indexes - 0-15: R0-R15 (13 == R13 reserved => is banked ... Has to be read as PSP / MSP. Decision has to be done by J-Link DLL side!) - 16: XPSR - 17: MSP - 18: PSP - 19: CFBP CONTROL/FAULTMASK/BASEPRI/PRIMASK (packed into 4 bytes of word. CONTROL = CFBP[31:24], FAULTMASK = CFBP[16:23], BASEPRI = CFBP[15:8], PRIMASK = CFBP[7:0] - 20: FPSCR - 21-52: FPS0-FPS31 - - - Register usage when entering this "subroutine": - R0 Cmd - R1 ParamInfo - R2 --- - R3 = &_SYSTEM_DCRDR (allows also access to DEMCR with offset) - R12 --- - - Table B1-9 EXC_RETURN definition of exception return behavior, with FP extension - LR Return to Return SP Frame type - --------------------------------------------------------- - 0xFFFFFFE1 Handler mode. MSP Extended - 0xFFFFFFE9 Thread mode MSP Extended - 0xFFFFFFED Thread mode PSP Extended - 0xFFFFFFF1 Handler mode. MSP Basic - 0xFFFFFFF9 Thread mode MSP Basic - 0xFFFFFFFD Thread mode PSP Basic - - So LR[2] == 1 => Return stack == PSP else MSP - - R0-R3, R12, PC, xPSR can be written via application stackpointer - Other regs can be written directly - - - Read register data from J-Link into R0 - */ - LDR R0,[R3, #+_SYSTEM_DEMCR_OFF] // _SYSTEM_DEMCR |= (1uL << 19); => Monitor is ready to receive register data - ORR R0,R0,#0x80000 - STR R0,[R3, #+_SYSTEM_DEMCR_OFF] -_HandleWRegWaitUntilDataRecv: - LDR R0,[R3, #+_SYSTEM_DEMCR_OFF] - LSLS R0,R0,#+12 - BMI.N _HandleWRegWaitUntilDataRecv // DEMCR[19] == 0 => J-Link has placed new data for us - LDR R0,[R3, #+_SYSTEM_DCRDR_OFF] // Get register data - // - // Determine application SP - // - LSRS R2,LR,#+3 // Shift LR[2] into carry => Carry clear means that CPU was running on MSP - ITE CS - MRSCS R2,PSP - MRSCC R2,MSP - CMP R1,#+4 // if (RegIndex < 4) { (R0-R3) - BCS _HandleWriteRegR4 - STR R0,[R2, R1, LSL #+2] // v = [SP + Rx * 4] (R0-R3) - B.N _HandleWriteRegDone -_HandleWriteRegR4: - CMP R1,#+5 // if (RegIndex < 5) { (R4) - BCS _HandleWriteRegR5 - MOV R4,R0 - B.N _HandleWriteRegDone -_HandleWriteRegR5: - CMP R1,#+6 // if (RegIndex < 6) { (R5) - BCS _HandleWriteRegR6 - MOV R5,R0 - B.N _HandleWriteRegDone -_HandleWriteRegR6: - CMP R1,#+7 // if (RegIndex < 7) { (R6) - BCS _HandleWriteRegR7 - MOV R6,R0 - B.N _HandleWriteRegDone -_HandleWriteRegR7: - CMP R1,#+8 // if (RegIndex < 8) { (R7) - BCS _HandleWriteRegR8 - MOV R7,R0 - B.N _HandleWriteRegDone -_HandleWriteRegR8: - CMP R1,#+9 // if (RegIndex < 9) { (R8) - BCS _HandleWriteRegR9 - MOV R8,R0 - B.N _HandleWriteRegDone -_HandleWriteRegR9: - CMP R1,#+10 // if (RegIndex < 10) { (R9) - BCS _HandleWriteRegR10 - MOV R9,R0 - B.N _HandleWriteRegDone -_HandleWriteRegR10: - CMP R1,#+11 // if (RegIndex < 11) { (R10) - BCS _HandleWriteRegR11 - MOV R10,R0 - B.N _HandleWriteRegDone -_HandleWriteRegR11: - CMP R1,#+12 // if (RegIndex < 12) { (R11) - BCS _HandleWriteRegR12 - MOV R11,R0 - B.N _HandleWriteRegDone -_HandleWriteRegR12: - CMP R1,#+14 // if (RegIndex < 14) { (R12) - BCS _HandleWriteRegR14 - STR R0,[R2, #+_APP_SP_OFF_R12] - B.N _HandleWriteRegDone -_HandleWriteRegR14: - CMP R1,#+15 // if (RegIndex < 15) { (R14 / LR) - BCS _HandleWriteRegR15 - STR R0,[R2, #+_APP_SP_OFF_R14_LR] - B.N _HandleWriteRegDone -_HandleWriteRegR15: - CMP R1,#+16 // if (RegIndex < 16) { (R15 / PC) - BCS _HandleWriteRegXPSR - STR R0,[R2, #+_APP_SP_OFF_PC] - B.N _HandleWriteRegDone -_HandleWriteRegXPSR: - CMP R1,#+17 // if (RegIndex < 17) { (xPSR) - BCS _HandleWriteRegMSP - STR R0,[R2, #+_APP_SP_OFF_XPSR] - B.N _HandleWriteRegDone -_HandleWriteRegMSP: - // - // For now, SP cannot be modified because it is needed to jump back from monitor mode - // - CMP R1,#+18 // if (RegIndex < 18) { (MSP) - BCS _HandleWriteRegPSP - B.N _HandleWriteRegDone -_HandleWriteRegPSP: // RegIndex == 18 - CMP R1,#+19 // if (RegIndex < 19) { - BCS _HandleWriteRegCFBP - B.N _HandleWriteRegDone -_HandleWriteRegCFBP: - /* - CFBP is a register that can only be read via debug probe and is a merger of the following regs: - CONTROL/FAULTMASK/BASEPRI/PRIMASK (packed into 4 bytes of word. CONTROL = CFBP[31:24], FAULTMASK = CFBP[16:23], BASEPRI = CFBP[15:8], PRIMASK = CFBP[7:0] - To keep J-Link side the same for monitor and halt mode, we also return CFBP in monitor mode - */ - CMP R1,#+20 // if (RegIndex < 20) { (CFBP) - BCS _HandleWriteRegFPU - LSLS R1,R0,#+24 - LSRS R1,R1,#+24 // Extract CFBP[7:0] => PRIMASK - MSR PRIMASK,R1 - LSLS R1,R0,#+16 - LSRS R1,R1,#+24 // Extract CFBP[15:8] => BASEPRI - MSR BASEPRI,R1 - LSLS R1,R0,#+8 // Extract CFBP[23:16] => FAULTMASK - LSRS R1,R1,#+24 - MSR FAULTMASK,R1 - LSRS R1,R0,#+24 // Extract CFBP[31:24] => CONTROL - LSRS R0,R1,#2 // Current CONTROL[1] -> Carry - ITE CS // Update saved CONTROL.SPSEL (CONTROL[1]). CONTROL.SPSEL is saved to LR[2] on exception entry => ARM DDI0403D, B1.5.6 Exception entry behavior - ORRCS LR,LR,#+4 - BICCC LR,LR,#+4 - BIC R1,R1,#+2 // CONTROL.SPSEL (CONTROL[1]) == 0 inside monitor. Otherwise behavior is UNPREDICTABLE - LSRS R0,R1,#+3 // New CONTROL.FPCA (CONTROL[2]) -> Carry - ITE CS // CONTROL[2] == FPCA => NOT(FPCA) saved to LR[4]. LR[4] == 0 => Extended stack frame, so FPU regs possibly on stack - BICCS LR,LR,#+0x10 // Remember: NOT(FPCA) is stored to LR. == 0 means: Extended stack frame - ORRCC LR,LR,#+0x10 - MRS R0,CONTROL - LSRS R0,R0,#+3 // CONTROL[2] -> Carry - ITE CS // Preserve original value of current CONTROL[2] - ORRCS R1,R1,#+0x04 - BICCC R1,R1,#+0x04 - MSR CONTROL,R1 - ISB // Necessary after writing to CONTROL, see ARM DDI0403D, B1.4.4 The special-purpose CONTROL register - B.N _HandleWriteRegDone -_HandleWriteRegFPU: -#if _HAS_FPU_REGS - CMP R1,#+53 // if (RegIndex < 53) { (20 (FPSCR), 21-52 FPS0-FPS31) - BCS _HandleWriteRegDone_Veneer - /* - Read Coprocessor Access Control Register (CPACR) to check if CP10 and CP11 are enabled - If not, access to floating point is not possible - CPACR[21:20] == CP10 enable. 0b01 = Privileged access only. 0b11 = Full access. Other = reserved - CPACR[23:22] == CP11 enable. 0b01 = Privileged access only. 0b11 = Full access. Other = reserved - */ - MOV R12,R0 // Save register data - LDR R0,_AddrCPACR - LDR R0,[R0] - LSLS R0,R0,#+8 - LSRS R0,R0,#+28 - CMP R0,#+0xF - BEQ _HandleWriteRegFPU_Allowed - CMP R0,#+0x5 - BNE _HandleWriteRegDone_Veneer -_HandleWriteRegFPU_Allowed: - CMP R1,#+21 // if (RegIndex < 21) (20 == FPSCR) - BCS _HandleWriteRegFPS0_FPS31 - LSRS R0,LR,#+5 // CONTROL[2] == FPCA => NOT(FPCA) saved to LR[4]. LR[4] == 0 => Extended stack frame, so FPU regs possibly on stack - BCS _HandleWriteFPSCRLazyMode // Remember: NOT(FPCA) is stored to LR. == 0 means: Extended stack frame - LDR R0,=_SYSTEM_FPCCR - LDR R0,[R0] - LSLS R0,R0,#+2 // FPCCR[30] -> Carry == 1 indicates if lazy mode is active, so space on stack is reserved but FPU registers are not saved on stack - BCS _HandleWriteFPSCRLazyMode - STR R12,[R2, #+_APP_SP_OFF_FPSCR] - B _HandleWriteRegDone -_HandleWriteFPSCRLazyMode: - VMSR FPSCR,R12 - B _HandleWriteRegDone -_HandleWriteRegFPS0_FPS31: // RegIndex == 21-52 - LDR R0,=_SYSTEM_FPCCR - LDR R0,[R0] - LSLS R0,R0,#+2 // FPCCR[30] -> Carry == 1 indicates if lazy mode is active, so space on stack is reserved but FPU registers are not saved on stack - BCS _HandleWriteFPS0_FPS31LazyMode - LSRS R0,LR,#+5 // CONTROL[2] == FPCA => NOT(FPCA) saved to LR[4]. LR[4] == 0 => Extended stack frame, so FPU regs possibly on stack - BCS _HandleWriteFPS0_FPS31LazyMode // Remember: NOT(FPCA) is stored to LR. == 0 means: Extended stack frame - SUBS R1,#+21 // Convert absolute reg index into rel. one - LSLS R1,R1,#+2 // RegIndex to position on stack - ADDS R1,#+_APP_SP_OFF_S0 - STR R12,[R2, R1] -_HandleWriteRegDone_Veneer: - B _HandleWriteRegDone -_HandleWriteFPS0_FPS31LazyMode: - SUBS R1,#+20 // Convert abs. RegIndex into rel. one - MOVS R0,#+6 - MULS R1,R0,R1 - LDR R0,=_HandleReadRegUnknown - SUB R0,R0,R1 // _HandleReadRegUnknown - 6 * ((RegIndex - 21) + 1) - ORR R0,R0,#1 // Thumb bit needs to be set in DestAddr - BX R0 - // - // Table for reading FPS0-FPS31 - // - VMOV S31,R12 // v = FPSx - B _HandleWriteRegDone - VMOV S30,R12 - B _HandleWriteRegDone - VMOV S29,R12 - B _HandleWriteRegDone - VMOV S28,R12 - B _HandleWriteRegDone - VMOV S27,R12 - B _HandleWriteRegDone - VMOV S26,R12 - B _HandleWriteRegDone - VMOV S25,R12 - B _HandleWriteRegDone - VMOV S24,R12 - B _HandleWriteRegDone - VMOV S23,R12 - B _HandleWriteRegDone - VMOV S22,R12 - B _HandleWriteRegDone - VMOV S21,R12 - B _HandleWriteRegDone - VMOV S20,R12 - B _HandleWriteRegDone - VMOV S19,R12 - B _HandleWriteRegDone - VMOV S18,R12 - B _HandleWriteRegDone - VMOV S17,R12 - B _HandleWriteRegDone - VMOV S16,R12 - B _HandleWriteRegDone - VMOV S15,R12 - B _HandleWriteRegDone - VMOV S14,R12 - B _HandleWriteRegDone - VMOV S13,R12 - B _HandleWriteRegDone - VMOV S12,R12 - B _HandleWriteRegDone - VMOV S11,R12 - B _HandleWriteRegDone - VMOV S10,R12 - B _HandleWriteRegDone - VMOV S9,R12 - B _HandleWriteRegDone - VMOV S8,R12 - B _HandleWriteRegDone - VMOV S7,R12 - B _HandleWriteRegDone - VMOV S6,R12 - B _HandleWriteRegDone - VMOV S5,R12 - B _HandleWriteRegDone - VMOV S4,R12 - B _HandleWriteRegDone - VMOV S3,R12 - B _HandleWriteRegDone - VMOV S2,R12 - B _HandleWriteRegDone - VMOV S1,R12 - B _HandleWriteRegDone - VMOV S0,R12 - B _HandleWriteRegDone -#else - B _HandleWriteRegUnknown -#endif -_HandleWriteRegUnknown: - B.N _HandleWriteRegDone -_HandleWriteRegDone: - B _IndicateMonReady // Indicate that monitor has read data, processed command and is ready for a new one - .end -/****** End Of File *************************************************/ From 783466f1165aeddd41ab1b1b76ef70aa2908c3b1 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Sat, 5 Oct 2024 05:24:59 -0500 Subject: [PATCH 58/88] Revert "Remove unused Jlink monitoring files (#4953)" (#4959) This reverts commit 55049ed547103787d700e0df5331f88755b89d8d. --- src/platform/nrf52/JLINK_MONITOR.c | 124 +++ src/platform/nrf52/JLINK_MONITOR.h | 27 + src/platform/nrf52/JLINK_MONITOR_ISR_SES.S | 888 +++++++++++++++++++++ 3 files changed, 1039 insertions(+) create mode 100644 src/platform/nrf52/JLINK_MONITOR.c create mode 100644 src/platform/nrf52/JLINK_MONITOR.h create mode 100644 src/platform/nrf52/JLINK_MONITOR_ISR_SES.S diff --git a/src/platform/nrf52/JLINK_MONITOR.c b/src/platform/nrf52/JLINK_MONITOR.c new file mode 100644 index 000000000..160264905 --- /dev/null +++ b/src/platform/nrf52/JLINK_MONITOR.c @@ -0,0 +1,124 @@ +/********************************************************************* +* SEGGER Microcontroller GmbH & Co. KG * +* The Embedded Experts * +********************************************************************** +* * +* (c) 1995 - 2015 SEGGER Microcontroller GmbH & Co. KG * +* * +* www.segger.com Support: support@segger.com * +* * +********************************************************************** + +---------------------------------------------------------------------- +File : JLINK_MONITOR.c +Purpose : Implementation of debug monitor for J-Link monitor mode debug on Cortex-M devices. +-------- END-OF-HEADER --------------------------------------------- +*/ + +#include "JLINK_MONITOR.h" + +/********************************************************************* + * + * Configuration + * + ********************************************************************** + */ + +/********************************************************************* + * + * Defines + * + ********************************************************************** + */ + +/********************************************************************* + * + * Types + * + ********************************************************************** + */ + +/********************************************************************* + * + * Static data + * + ********************************************************************** + */ + +volatile int MAIN_MonCnt; // Incremented in JLINK_MONITOR_OnPoll() while CPU is in debug mode + +/********************************************************************* + * + * Local functions + * + ********************************************************************** + */ + +/********************************************************************* + * + * Global functions + * + ********************************************************************** + */ + +/********************************************************************* + * + * JLINK_MONITOR_OnExit() + * + * Function description + * Called from DebugMon_Handler(), once per debug exit. + * May perform some target specific operations to be done on debug mode exit. + * + * Notes + * (1) Must not keep the CPU busy for more than 100 ms + */ +void JLINK_MONITOR_OnExit(void) +{ + // + // Add custom code here + // + // BSP_ClrLED(0); +} + +/********************************************************************* + * + * JLINK_MONITOR_OnEnter() + * + * Function description + * Called from DebugMon_Handler(), once per debug entry. + * May perform some target specific operations to be done on debug mode entry + * + * Notes + * (1) Must not keep the CPU busy for more than 100 ms + */ +void JLINK_MONITOR_OnEnter(void) +{ + // + // Add custom code here + // + // BSP_SetLED(0); + // BSP_ClrLED(1); +} + +/********************************************************************* + * + * JLINK_MONITOR_OnPoll() + * + * Function description + * Called periodically from DebugMon_Handler(), to perform some actions that need to be performed periodically during debug + * mode. + * + * Notes + * (1) Must not keep the CPU busy for more than 100 ms + */ +void JLINK_MONITOR_OnPoll(void) +{ + // + // Add custom code here + // + MAIN_MonCnt++; + // BSP_ToggleLED(0); + // _Delay(500000); +} + +/****** End Of File *************************************************/ diff --git a/src/platform/nrf52/JLINK_MONITOR.h b/src/platform/nrf52/JLINK_MONITOR.h new file mode 100644 index 000000000..87cf332fe --- /dev/null +++ b/src/platform/nrf52/JLINK_MONITOR.h @@ -0,0 +1,27 @@ +/********************************************************************* +* SEGGER Microcontroller GmbH & Co. KG * +* The Embedded Experts * +********************************************************************** +* * +* (c) 1995 - 2015 SEGGER Microcontroller GmbH & Co. KG * +* * +* www.segger.com Support: support@segger.com * +* * +********************************************************************** + +---------------------------------------------------------------------- +File : JLINK_MONITOR.h +Purpose : Header file of debug monitor for J-Link monitor mode debug on Cortex-M devices. +-------- END-OF-HEADER --------------------------------------------- +*/ + +#ifndef JLINK_MONITOR_H +#define JLINK_MONITOR_H + +void JLINK_MONITOR_OnExit(void); +void JLINK_MONITOR_OnEnter(void); +void JLINK_MONITOR_OnPoll(void); + +#endif + +/****** End Of File *************************************************/ diff --git a/src/platform/nrf52/JLINK_MONITOR_ISR_SES.S b/src/platform/nrf52/JLINK_MONITOR_ISR_SES.S new file mode 100644 index 000000000..cda4b1a50 --- /dev/null +++ b/src/platform/nrf52/JLINK_MONITOR_ISR_SES.S @@ -0,0 +1,888 @@ +/********************************************************************* +* SEGGER Microcontroller GmbH & Co. KG * +* The Embedded Experts * +********************************************************************** +* * +* (c) 1995 - 2015 SEGGER Microcontroller GmbH & Co. KG * +* * +* www.segger.com Support: support@segger.com * +* * +********************************************************************** + +---------------------------------------------------------------------- +File : JLINK_MONITOR_ISR_SES.s +Purpose : Implementation of debug monitor for J-Link monitor mode + debug on Cortex-M devices, supporting SES compiler. +-------- END-OF-HEADER --------------------------------------------- +*/ + + .name JLINK_MONITOR_ISR + .syntax unified + + .extern JLINK_MONITOR_OnEnter + .extern JLINK_MONITOR_OnExit + .extern JLINK_MONITOR_OnPoll + + .global DebugMon_Handler + +/********************************************************************* +* +* Defines, configurable +* +********************************************************************** +*/ + +#define _MON_VERSION 100 // V x.yy + +/********************************************************************* +* +* Defines, fixed +* +********************************************************************** +*/ + +#define _APP_SP_OFF_R0 0x00 +#define _APP_SP_OFF_R1 0x04 +#define _APP_SP_OFF_R2 0x08 +#define _APP_SP_OFF_R3 0x0C +#define _APP_SP_OFF_R12 0x10 +#define _APP_SP_OFF_R14_LR 0x14 +#define _APP_SP_OFF_PC 0x18 +#define _APP_SP_OFF_XPSR 0x1C +#define _APP_SP_OFF_S0 0x20 +#define _APP_SP_OFF_S1 0x24 +#define _APP_SP_OFF_S2 0x28 +#define _APP_SP_OFF_S3 0x2C +#define _APP_SP_OFF_S4 0x30 +#define _APP_SP_OFF_S5 0x34 +#define _APP_SP_OFF_S6 0x38 +#define _APP_SP_OFF_S7 0x3C +#define _APP_SP_OFF_S8 0x40 +#define _APP_SP_OFF_S9 0x44 +#define _APP_SP_OFF_S10 0x48 +#define _APP_SP_OFF_S11 0x4C +#define _APP_SP_OFF_S12 0x50 +#define _APP_SP_OFF_S13 0x54 +#define _APP_SP_OFF_S14 0x58 +#define _APP_SP_OFF_S15 0x5C +#define _APP_SP_OFF_FPSCR 0x60 + +#define _NUM_BYTES_BASIC_STACKFRAME 32 +#define _NUM_BYTES_EXTENDED_STACKFRAME 72 + +#define _SYSTEM_DCRDR_OFF 0x00 +#define _SYSTEM_DEMCR_OFF 0x04 + +#define _SYSTEM_DHCSR 0xE000EDF0 // Debug Halting Control and Status Register (DHCSR) +#define _SYSTEM_DCRSR 0xE000EDF4 // Debug Core Register Selector Register (DCRSR) +#define _SYSTEM_DCRDR 0xE000EDF8 // Debug Core Register Data Register (DCRDR) +#define _SYSTEM_DEMCR 0xE000EDFC // Debug Exception and Monitor Control Register (DEMCR) + +#define _SYSTEM_FPCCR 0xE000EF34 // Floating-Point Context Control Register (FPCCR) +#define _SYSTEM_FPCAR 0xE000EF38 // Floating-Point Context Address Register (FPCAR) +#define _SYSTEM_FPDSCR 0xE000EF3C // Floating-Point Default Status Control Register (FPDSCR) +#define _SYSTEM_MVFR0 0xE000EF40 // Media and FP Feature Register 0 (MVFR0) +#define _SYSTEM_MVFR1 0xE000EF44 // Media and FP Feature Register 1 (MVFR1) + +/* +* Defines for determining if the current debug config supports FPU registers +* For some compilers like IAR EWARM when disabling the FPU in the compiler settings an error is thrown when +*/ +#ifdef __FPU_PRESENT + #if __FPU_PRESENT + #define _HAS_FPU_REGS 1 + #else + #define _HAS_FPU_REGS 0 + #endif +#else + #define _HAS_FPU_REGS 0 +#endif + +/********************************************************************* +* +* Signature of monitor +* +* Function description +* Needed for targets where also a boot ROM is present that possibly specifies a vector table with a valid debug monitor exception entry +*/ + .section .text, "ax" + + // + // JLINKMONHANDLER + // + .byte 0x4A + .byte 0x4C + .byte 0x49 + .byte 0x4E + .byte 0x4B + .byte 0x4D + .byte 0x4F + .byte 0x4E + .byte 0x48 + .byte 0x41 + .byte 0x4E + .byte 0x44 + .byte 0x4C + .byte 0x45 + .byte 0x52 + .byte 0x00 // Align to 8-bytes + +/********************************************************************* +* +* DebugMon_Handler() +* +* Function description +* Debug monitor handler. CPU enters this handler in case a "halt" request is made from the debugger. +* This handler is also responsible for handling commands that are sent by the debugger. +* +* Notes +* This is actually the ISR for the debug interrupt (exception no. 12) +*/ + .thumb_func + +DebugMon_Handler: + /* + General procedure: + DCRDR is used as communication register + DEMCR[19] is used as ready flag + For the command J-Link sends to the monitor: DCRDR[7:0] == Cmd, DCRDR[31:8] == ParamData + + 1) Monitor sets DEMCR[19] whenever it is ready to receive new commands/data + DEMCR[19] is initially set on debug monitor entry + 2) J-Link will clear once it has placed conmmand/data in DCRDR for J-Link + 3) Monitor will wait for DEMCR[19] to be cleared + 4) Monitor will process command (May cause additional data transfers etc., depends on command + 5) No restart-CPU command? => Back to 2), Otherwise => 6) + 6) Monitor will clear DEMCR[19] 19 to indicate that it is no longer ready + */ + PUSH {LR} + BL JLINK_MONITOR_OnEnter + POP {LR} + LDR.N R3,_AddrDCRDR // 0xe000edf8 == _SYSTEM_DCRDR + B.N _IndicateMonReady +_WaitProbeReadIndicateMonRdy: // while(_SYSTEM_DEMCR & (1uL << 19)); => Wait until J-Link has read item + LDR R0,[R3, #+_SYSTEM_DEMCR_OFF] // _SYSTEM_DEMCR + LSLS R0,R0,#+12 + BMI.N _WaitProbeReadIndicateMonRdy +_IndicateMonReady: + LDR R0,[R3, #+_SYSTEM_DEMCR_OFF] // _SYSTEM_DEMCR |= (1uL << 19); => Set MON_REQ bit, so J-Link knows monitor is ready to receive commands + ORR R0,R0,#0x80000 + STR R0,[R3, #+_SYSTEM_DEMCR_OFF] + /* + During command loop: + R0 = Tmp + R1 = Tmp + R2 = Tmp + R3 = &_SYSTEM_DCRDR (allows also access to DEMCR with offset) + R12 = Tmp + + Outside command loop R0-R3 and R12 may be overwritten by MONITOR_OnPoll() + */ +_WaitForJLinkCmd: // do { + PUSH {LR} + BL JLINK_MONITOR_OnPoll + POP {LR} + LDR.N R3,_AddrDCRDR // 0xe000edf8 == _SYSTEM_DCRDR + LDR R0,[R3, #+_SYSTEM_DEMCR_OFF] + LSRS R0,R0,#+20 // DEMCR[19] -> Carry Clear? => J-Link has placed command for us + BCS _WaitForJLinkCmd + /* + Perform command + Command is placed by J-Link in DCRDR[7:0] and additional parameter data is stored in DCRDR[31:8] + J-Link clears DEMCR[19] to indicate that it placed a command/data or read data + Monitor sets DEMCR[19] to indicate that it placed data or read data / is ready for a new command + Setting DEMCR[19] indicates "monitor ready for new command / data" and also indicates: "data has been placed in DCRDR by monitor, for J-Link" + Therefore it is responsibility of the commands to respond to the commands accordingly + + Commands for debug monitor + Commands must not exceed 0xFF (255) as we only defined 8-bits for command-part. Higher 24-bits are parameter info for current command + + Protocol for different commands: + J-Link: Cmd -> DCRDR, DEMCR[19] -> 0 => Cmd placed by probe + */ + LDR R0,[R3, #+_SYSTEM_DCRDR_OFF] // ParamInfo = _SYSTEM_DCRDR + LSRS R1,R0,#+8 // ParamInfo >>= 8 + LSLS R0,R0,#+24 + LSRS R0,R0,#+24 // Cmd = ParamInfo & 0xFF + // + // switch (Cmd) + // + CMP R0,#+0 + BEQ.N _HandleGetMonVersion // case _MON_CMD_GET_MONITOR_VERSION + CMP R0,#+2 + BEQ.N _HandleReadReg // case _MON_CMD_READ_REG + BCC.N _HandleRestartCPU // case _MON_CMD_RESTART_CPU + CMP R0,#+3 + BEQ.N _HandleWriteReg_Veneer // case _MON_CMD_WRITE_REG + B.N _IndicateMonReady // default : while (1); + /* + Return + _MON_CMD_RESTART_CPU + CPU: DEMCR[19] -> 0 => Monitor no longer ready + */ +_HandleRestartCPU: + LDR R0,[R3, #+_SYSTEM_DEMCR_OFF] // _SYSTEM_DEMCR &= ~(1uL << 19); => Clear MON_REQ to indicate that monitor is no longer active + BIC R0,R0,#0x80000 + STR R0,[R3, #+_SYSTEM_DEMCR_OFF] + PUSH {LR} + BL JLINK_MONITOR_OnExit + POP {PC} + // + // Place data section here to not get in trouble with load-offsets + // + .section .text, "ax", %progbits + .align 2 +_AddrDCRDR: + .long 0xE000EDF8 +_AddrCPACR: + .long 0xE000ED88 + + .section .text, "ax" + .thumb_func + +;/********************************************************************* +;* +;* _HandleGetMonVersion +;* +;*/ +_HandleGetMonVersion: + /* + _MON_CMD_GET_MONITOR_VERSION + CPU: Data -> DCRDR, DEMCR[19] -> 1 => Data ready + J-Link: DCRDR -> Read, DEMCR[19] -> 0 => Data read + CPU: DEMCR[19] -> 1 => Mon ready + */ + MOVS R0,#+_MON_VERSION + STR R0,[R3, #+_SYSTEM_DCRDR_OFF] // _SYSTEM_DCRDR = x + LDR R0,[R3, #+_SYSTEM_DEMCR_OFF] // _SYSTEM_DEMCR |= (1uL << 19); => Set MON_REQ bit, so J-Link knows monitor is ready to receive commands + ORR R0,R0,#0x80000 + STR R0,[R3, #+_SYSTEM_DEMCR_OFF] // Indicate data ready + B _WaitProbeReadIndicateMonRdy + +/********************************************************************* +* +* _HandleReadReg +* +*/ +_HandleWriteReg_Veneer: + B.N _HandleWriteReg +_HandleReadReg: + /* + _MON_CMD_READ_REG + CPU: Data -> DCRDR, DEMCR[19] -> 1 => Data ready + J-Link: DCRDR -> Read, DEMCR[19] -> 0 => Data read + CPU: DEMCR[19] -> 1 => Mon ready + + + Register indexes + 0-15: R0-R15 (13 == R13 reserved => is banked ... Has to be read as PSP / MSP. Decision has to be done by J-Link DLL side!) + 16: XPSR + 17: MSP + 18: PSP + 19: CFBP CONTROL/FAULTMASK/BASEPRI/PRIMASK (packed into 4 bytes of word. CONTROL = CFBP[31:24], FAULTMASK = CFBP[16:23], BASEPRI = CFBP[15:8], PRIMASK = CFBP[7:0] + 20: FPSCR + 21-52: FPS0-FPS31 + + + Register usage when entering this "subroutine": + R0 Cmd + R1 ParamInfo + R2 --- + R3 = &_SYSTEM_DCRDR (allows also access to DEMCR with offset) + R12 --- + + Table B1-9 EXC_RETURN definition of exception return behavior, with FP extension + LR Return to Return SP Frame type + --------------------------------------------------------- + 0xFFFFFFE1 Handler mode. MSP Extended + 0xFFFFFFE9 Thread mode MSP Extended + 0xFFFFFFED Thread mode PSP Extended + 0xFFFFFFF1 Handler mode. MSP Basic + 0xFFFFFFF9 Thread mode MSP Basic + 0xFFFFFFFD Thread mode PSP Basic + + So LR[2] == 1 => Return stack == PSP else MSP + + R0-R3, R12, PC, xPSR can be read from application stackpointer + Other regs can be read directly + */ + LSRS R2,LR,#+3 // Shift LR[2] into carry => Carry clear means that CPU was running on MSP + ITE CS + MRSCS R2,PSP + MRSCC R2,MSP + CMP R1,#+4 // if (RegIndex < 4) { (R0-R3) + BCS _HandleReadRegR4 + LDR R0,[R2, R1, LSL #+2] // v = [SP + Rx * 4] (R0-R3) + B.N _HandleReadRegDone +_HandleReadRegR4: + CMP R1,#+5 // if (RegIndex < 5) { (R4) + BCS _HandleReadRegR5 + MOV R0,R4 + B.N _HandleReadRegDone +_HandleReadRegR5: + CMP R1,#+6 // if (RegIndex < 6) { (R5) + BCS _HandleReadRegR6 + MOV R0,R5 + B.N _HandleReadRegDone +_HandleReadRegR6: + CMP R1,#+7 // if (RegIndex < 7) { (R6) + BCS _HandleReadRegR7 + MOV R0,R6 + B.N _HandleReadRegDone +_HandleReadRegR7: + CMP R1,#+8 // if (RegIndex < 8) { (R7) + BCS _HandleReadRegR8 + MOV R0,R7 + B.N _HandleReadRegDone +_HandleReadRegR8: + CMP R1,#+9 // if (RegIndex < 9) { (R8) + BCS _HandleReadRegR9 + MOV R0,R8 + B.N _HandleReadRegDone +_HandleReadRegR9: + CMP R1,#+10 // if (RegIndex < 10) { (R9) + BCS _HandleReadRegR10 + MOV R0,R9 + B.N _HandleReadRegDone +_HandleReadRegR10: + CMP R1,#+11 // if (RegIndex < 11) { (R10) + BCS _HandleReadRegR11 + MOV R0,R10 + B.N _HandleReadRegDone +_HandleReadRegR11: + CMP R1,#+12 // if (RegIndex < 12) { (R11) + BCS _HandleReadRegR12 + MOV R0,R11 + B.N _HandleReadRegDone +_HandleReadRegR12: + CMP R1,#+14 // if (RegIndex < 14) { (R12) + BCS _HandleReadRegR14 + LDR R0,[R2, #+_APP_SP_OFF_R12] + B.N _HandleReadRegDone +_HandleReadRegR14: + CMP R1,#+15 // if (RegIndex < 15) { (R14 / LR) + BCS _HandleReadRegR15 + LDR R0,[R2, #+_APP_SP_OFF_R14_LR] + B.N _HandleReadRegDone +_HandleReadRegR15: + CMP R1,#+16 // if (RegIndex < 16) { (R15 / PC) + BCS _HandleReadRegXPSR + LDR R0,[R2, #+_APP_SP_OFF_PC] + B.N _HandleReadRegDone +_HandleReadRegXPSR: + CMP R1,#+17 // if (RegIndex < 17) { (xPSR) + BCS _HandleReadRegMSP + LDR R0,[R2, #+_APP_SP_OFF_XPSR] + B.N _HandleReadRegDone +_HandleReadRegMSP: + /* + Stackpointer is tricky because we need to get some info about the SP used in the user app, first + + Handle reading R0-R3 which can be read right from application stackpointer + + Table B1-9 EXC_RETURN definition of exception return behavior, with FP extension + LR Return to Return SP Frame type + --------------------------------------------------------- + 0xFFFFFFE1 Handler mode. MSP Extended + 0xFFFFFFE9 Thread mode MSP Extended + 0xFFFFFFED Thread mode PSP Extended + 0xFFFFFFF1 Handler mode. MSP Basic + 0xFFFFFFF9 Thread mode MSP Basic + 0xFFFFFFFD Thread mode PSP Basic + + So LR[2] == 1 => Return stack == PSP else MSP + Per architecture definition: Inside monitor (exception) SP = MSP + + Stack pointer handling is complicated because it is different what is pushed on the stack before entering the monitor ISR... + Cortex-M: 8 regs + Cortex-M + forced-stack-alignment: 8 regs + 1 dummy-word if stack was not 8-byte aligned + Cortex-M + FPU: 8 regs + 17 FPU regs + 1 dummy-word + 1-dummy word if stack was not 8-byte aligned + Cortex-M + FPU + lazy mode: 8 regs + 17 dummy-words + 1 dummy-word + 1-dummy word if stack was not 8-byte aligned + */ + CMP R1,#+18 // if (RegIndex < 18) { (MSP) + BCS _HandleReadRegPSP + MRS R0,MSP + LSRS R1,LR,#+3 // LR[2] -> Carry == 0 => CPU was running on MSP => Needs correction + BCS _HandleReadRegDone_Veneer // CPU was running on PSP? => No correction necessary +_HandleSPCorrection: + LSRS R1,LR,#+5 // LR[4] -> Carry == 0 => extended stack frame has been allocated. See ARM DDI0403D, B1.5.7 Stack alignment on exception entry + ITE CS + ADDCS R0,R0,#+_NUM_BYTES_BASIC_STACKFRAME + ADDCC R0,R0,#+_NUM_BYTES_EXTENDED_STACKFRAME + LDR R1,[R2, #+_APP_SP_OFF_XPSR] // Get xPSR from application stack (R2 has been set to app stack on beginning of _HandleReadReg) + LSRS R1,R1,#+5 // xPSR[9] -> Carry == 1 => Stack has been force-aligned before pushing regs. See ARM DDI0403D, B1.5.7 Stack alignment on exception entry + IT CS + ADDCS R0,R0,#+4 + B _HandleReadRegDone +_HandleReadRegPSP: // RegIndex == 18 + CMP R1,#+19 // if (RegIndex < 19) { + BCS _HandleReadRegCFBP + MRS R0,PSP // PSP is not touched by monitor + LSRS R1,LR,#+3 // LR[2] -> Carry == 1 => CPU was running on PSP => Needs correction + BCC _HandleReadRegDone_Veneer // CPU was running on MSP? => No correction of PSP necessary + B _HandleSPCorrection +_HandleReadRegCFBP: + /* + CFBP is a register that can only be read via debug probe and is a merger of the following regs: + CONTROL/FAULTMASK/BASEPRI/PRIMASK (packed into 4 bytes of word. CONTROL = CFBP[31:24], FAULTMASK = CFBP[16:23], BASEPRI = CFBP[15:8], PRIMASK = CFBP[7:0] + To keep J-Link side the same for monitor and halt mode, we also return CFBP in monitor mode + */ + CMP R1,#+20 // if (RegIndex < 20) { (CFBP) + BCS _HandleReadRegFPU + MOVS R0,#+0 + MRS R2,PRIMASK + ORRS R0,R2 // Merge PRIMASK into CFBP[7:0] + MRS R2,BASEPRI + LSLS R2,R2,#+8 // Merge BASEPRI into CFBP[15:8] + ORRS R0,R2 + MRS R2,FAULTMASK + LSLS R2,R2,#+16 // Merge FAULTMASK into CFBP[23:16] + ORRS R0,R2 + MRS R2,CONTROL + LSRS R1,LR,#3 // LR[2] -> Carry. CONTROL.SPSEL is saved to LR[2] on exception entry => ARM DDI0403D, B1.5.6 Exception entry behavior + IT CS // As J-Link sees value of CONTROL at application time, we need reconstruct original value of CONTROL + ORRCS R2,R2,#+2 // CONTROL.SPSEL (CONTROL[1]) == 0 inside monitor + LSRS R1,LR,#+5 // LR[4] == NOT(CONTROL.FPCA) -> Carry + ITE CS // Merge original value of FPCA (CONTROL[2]) into read data + BICCS R2,R2,#+0x04 // Remember LR contains NOT(CONTROL) + ORRCC R2,R2,#+0x04 + LSLS R2,R2,#+24 + ORRS R0,R2 + B.N _HandleReadRegDone +_HandleReadRegFPU: +#if _HAS_FPU_REGS + CMP R1,#+53 // if (RegIndex < 53) { (20 (FPSCR), 21-52 FPS0-FPS31) + BCS _HandleReadRegDone_Veneer + /* + Read Coprocessor Access Control Register (CPACR) to check if CP10 and CP11 are enabled + If not, access to floating point is not possible + CPACR[21:20] == CP10 enable. 0b01 = Privileged access only. 0b11 = Full access. Other = reserved + CPACR[23:22] == CP11 enable. 0b01 = Privileged access only. 0b11 = Full access. Other = reserved + */ + LDR R0,_AddrCPACR + LDR R0,[R0] + LSLS R0,R0,#+8 + LSRS R0,R0,#+28 + CMP R0,#+0xF + BEQ _HandleReadRegFPU_Allowed + CMP R0,#+0x5 + BNE _HandleReadRegDone_Veneer +_HandleReadRegFPU_Allowed: + CMP R1,#+21 // if (RegIndex < 21) (20 == FPSCR) + BCS _HandleReadRegFPS0_FPS31 + LSRS R0,LR,#+5 // CONTROL[2] == FPCA => NOT(FPCA) saved to LR[4]. LR[4] == 0 => Extended stack frame, so FPU regs possibly on stack + BCS _HandleReadFPSCRLazyMode // Remember: NOT(FPCA) is stored to LR. == 0 means: Extended stack frame + LDR R0,=_SYSTEM_FPCCR + LDR R0,[R0] + LSLS R0,R0,#+2 // FPCCR[30] -> Carry == 1 indicates if lazy mode is active, so space on stack is reserved but FPU registers are not saved on stack + BCS _HandleReadFPSCRLazyMode + LDR R0,[R2, #+_APP_SP_OFF_FPSCR] + B _HandleReadRegDone +_HandleReadFPSCRLazyMode: + VMRS R0,FPSCR + B _HandleReadRegDone +_HandleReadRegFPS0_FPS31: // RegIndex == 21-52 + LSRS R0,LR,#+5 // CONTROL[2] == FPCA => NOT(FPCA) saved to LR[4]. LR[4] == 0 => Extended stack frame, so FPU regs possibly on stack + BCS _HandleReadFPS0_FPS31LazyMode // Remember: NOT(FPCA) is stored to LR. == 0 means: Extended stack frame + LDR R0,=_SYSTEM_FPCCR + LDR R0,[R0] + LSLS R0,R0,#+2 // FPCCR[30] -> Carry == 1 indicates if lazy mode is active, so space on stack is reserved but FPU registers are not saved on stack + BCS _HandleReadFPS0_FPS31LazyMode + SUBS R1,#+21 // Convert absolute reg index into rel. one + LSLS R1,R1,#+2 // RegIndex to position on stack + ADDS R1,#+_APP_SP_OFF_S0 + LDR R0,[R2, R1] +_HandleReadRegDone_Veneer: + B _HandleReadRegDone +_HandleReadFPS0_FPS31LazyMode: + SUBS R1,#+20 // convert abs. RegIndex into rel. one + MOVS R0,#+6 + MULS R1,R0,R1 + LDR R0,=_HandleReadRegUnknown + SUB R0,R0,R1 // _HandleReadRegUnknown - 6 * ((RegIndex - 21) + 1) + ORR R0,R0,#1 // Thumb bit needs to be set in DestAddr + BX R0 + // + // Table for reading FPS0-FPS31 + // + VMOV R0,S31 // v = FPSx + B _HandleReadRegDone + VMOV R0,S30 + B _HandleReadRegDone + VMOV R0,S29 + B _HandleReadRegDone + VMOV R0,S28 + B _HandleReadRegDone + VMOV R0,S27 + B _HandleReadRegDone + VMOV R0,S26 + B _HandleReadRegDone + VMOV R0,S25 + B _HandleReadRegDone + VMOV R0,S24 + B _HandleReadRegDone + VMOV R0,S23 + B _HandleReadRegDone + VMOV R0,S22 + B _HandleReadRegDone + VMOV R0,S21 + B _HandleReadRegDone + VMOV R0,S20 + B _HandleReadRegDone + VMOV R0,S19 + B _HandleReadRegDone + VMOV R0,S18 + B _HandleReadRegDone + VMOV R0,S17 + B _HandleReadRegDone + VMOV R0,S16 + B _HandleReadRegDone + VMOV R0,S15 + B _HandleReadRegDone + VMOV R0,S14 + B _HandleReadRegDone + VMOV R0,S13 + B _HandleReadRegDone + VMOV R0,S12 + B _HandleReadRegDone + VMOV R0,S11 + B _HandleReadRegDone + VMOV R0,S10 + B _HandleReadRegDone + VMOV R0,S9 + B _HandleReadRegDone + VMOV R0,S8 + B _HandleReadRegDone + VMOV R0,S7 + B _HandleReadRegDone + VMOV R0,S6 + B _HandleReadRegDone + VMOV R0,S5 + B _HandleReadRegDone + VMOV R0,S4 + B _HandleReadRegDone + VMOV R0,S3 + B _HandleReadRegDone + VMOV R0,S2 + B _HandleReadRegDone + VMOV R0,S1 + B _HandleReadRegDone + VMOV R0,S0 + B _HandleReadRegDone +#else + B _HandleReadRegUnknown +_HandleReadRegDone_Veneer: + B _HandleReadRegDone +#endif +_HandleReadRegUnknown: + MOVS R0,#+0 // v = 0 + B.N _HandleReadRegDone +_HandleReadRegDone: + + // Send register content to J-Link and wait until J-Link has read the data + + STR R0,[R3, #+_SYSTEM_DCRDR_OFF] // DCRDR = v; + LDR R0,[R3, #+_SYSTEM_DEMCR_OFF] // _SYSTEM_DEMCR |= (1uL << 19); => Set MON_REQ bit, so J-Link knows monitor is ready to receive commands + ORR R0,R0,#0x80000 + STR R0,[R3, #+_SYSTEM_DEMCR_OFF] // Indicate data ready + B _WaitProbeReadIndicateMonRdy + + // Data section for register addresses + +_HandleWriteReg: + /* + _MON_CMD_WRITE_REG + CPU: DEMCR[19] -> 1 => Mon ready + J-Link: Data -> DCRDR, DEMCR[19] -> 0 => Data placed by probe + CPU: DCRDR -> Read, Process command, DEMCR[19] -> 1 => Data read & mon ready + + Register indexes + 0-15: R0-R15 (13 == R13 reserved => is banked ... Has to be read as PSP / MSP. Decision has to be done by J-Link DLL side!) + 16: XPSR + 17: MSP + 18: PSP + 19: CFBP CONTROL/FAULTMASK/BASEPRI/PRIMASK (packed into 4 bytes of word. CONTROL = CFBP[31:24], FAULTMASK = CFBP[16:23], BASEPRI = CFBP[15:8], PRIMASK = CFBP[7:0] + 20: FPSCR + 21-52: FPS0-FPS31 + + + Register usage when entering this "subroutine": + R0 Cmd + R1 ParamInfo + R2 --- + R3 = &_SYSTEM_DCRDR (allows also access to DEMCR with offset) + R12 --- + + Table B1-9 EXC_RETURN definition of exception return behavior, with FP extension + LR Return to Return SP Frame type + --------------------------------------------------------- + 0xFFFFFFE1 Handler mode. MSP Extended + 0xFFFFFFE9 Thread mode MSP Extended + 0xFFFFFFED Thread mode PSP Extended + 0xFFFFFFF1 Handler mode. MSP Basic + 0xFFFFFFF9 Thread mode MSP Basic + 0xFFFFFFFD Thread mode PSP Basic + + So LR[2] == 1 => Return stack == PSP else MSP + + R0-R3, R12, PC, xPSR can be written via application stackpointer + Other regs can be written directly + + + Read register data from J-Link into R0 + */ + LDR R0,[R3, #+_SYSTEM_DEMCR_OFF] // _SYSTEM_DEMCR |= (1uL << 19); => Monitor is ready to receive register data + ORR R0,R0,#0x80000 + STR R0,[R3, #+_SYSTEM_DEMCR_OFF] +_HandleWRegWaitUntilDataRecv: + LDR R0,[R3, #+_SYSTEM_DEMCR_OFF] + LSLS R0,R0,#+12 + BMI.N _HandleWRegWaitUntilDataRecv // DEMCR[19] == 0 => J-Link has placed new data for us + LDR R0,[R3, #+_SYSTEM_DCRDR_OFF] // Get register data + // + // Determine application SP + // + LSRS R2,LR,#+3 // Shift LR[2] into carry => Carry clear means that CPU was running on MSP + ITE CS + MRSCS R2,PSP + MRSCC R2,MSP + CMP R1,#+4 // if (RegIndex < 4) { (R0-R3) + BCS _HandleWriteRegR4 + STR R0,[R2, R1, LSL #+2] // v = [SP + Rx * 4] (R0-R3) + B.N _HandleWriteRegDone +_HandleWriteRegR4: + CMP R1,#+5 // if (RegIndex < 5) { (R4) + BCS _HandleWriteRegR5 + MOV R4,R0 + B.N _HandleWriteRegDone +_HandleWriteRegR5: + CMP R1,#+6 // if (RegIndex < 6) { (R5) + BCS _HandleWriteRegR6 + MOV R5,R0 + B.N _HandleWriteRegDone +_HandleWriteRegR6: + CMP R1,#+7 // if (RegIndex < 7) { (R6) + BCS _HandleWriteRegR7 + MOV R6,R0 + B.N _HandleWriteRegDone +_HandleWriteRegR7: + CMP R1,#+8 // if (RegIndex < 8) { (R7) + BCS _HandleWriteRegR8 + MOV R7,R0 + B.N _HandleWriteRegDone +_HandleWriteRegR8: + CMP R1,#+9 // if (RegIndex < 9) { (R8) + BCS _HandleWriteRegR9 + MOV R8,R0 + B.N _HandleWriteRegDone +_HandleWriteRegR9: + CMP R1,#+10 // if (RegIndex < 10) { (R9) + BCS _HandleWriteRegR10 + MOV R9,R0 + B.N _HandleWriteRegDone +_HandleWriteRegR10: + CMP R1,#+11 // if (RegIndex < 11) { (R10) + BCS _HandleWriteRegR11 + MOV R10,R0 + B.N _HandleWriteRegDone +_HandleWriteRegR11: + CMP R1,#+12 // if (RegIndex < 12) { (R11) + BCS _HandleWriteRegR12 + MOV R11,R0 + B.N _HandleWriteRegDone +_HandleWriteRegR12: + CMP R1,#+14 // if (RegIndex < 14) { (R12) + BCS _HandleWriteRegR14 + STR R0,[R2, #+_APP_SP_OFF_R12] + B.N _HandleWriteRegDone +_HandleWriteRegR14: + CMP R1,#+15 // if (RegIndex < 15) { (R14 / LR) + BCS _HandleWriteRegR15 + STR R0,[R2, #+_APP_SP_OFF_R14_LR] + B.N _HandleWriteRegDone +_HandleWriteRegR15: + CMP R1,#+16 // if (RegIndex < 16) { (R15 / PC) + BCS _HandleWriteRegXPSR + STR R0,[R2, #+_APP_SP_OFF_PC] + B.N _HandleWriteRegDone +_HandleWriteRegXPSR: + CMP R1,#+17 // if (RegIndex < 17) { (xPSR) + BCS _HandleWriteRegMSP + STR R0,[R2, #+_APP_SP_OFF_XPSR] + B.N _HandleWriteRegDone +_HandleWriteRegMSP: + // + // For now, SP cannot be modified because it is needed to jump back from monitor mode + // + CMP R1,#+18 // if (RegIndex < 18) { (MSP) + BCS _HandleWriteRegPSP + B.N _HandleWriteRegDone +_HandleWriteRegPSP: // RegIndex == 18 + CMP R1,#+19 // if (RegIndex < 19) { + BCS _HandleWriteRegCFBP + B.N _HandleWriteRegDone +_HandleWriteRegCFBP: + /* + CFBP is a register that can only be read via debug probe and is a merger of the following regs: + CONTROL/FAULTMASK/BASEPRI/PRIMASK (packed into 4 bytes of word. CONTROL = CFBP[31:24], FAULTMASK = CFBP[16:23], BASEPRI = CFBP[15:8], PRIMASK = CFBP[7:0] + To keep J-Link side the same for monitor and halt mode, we also return CFBP in monitor mode + */ + CMP R1,#+20 // if (RegIndex < 20) { (CFBP) + BCS _HandleWriteRegFPU + LSLS R1,R0,#+24 + LSRS R1,R1,#+24 // Extract CFBP[7:0] => PRIMASK + MSR PRIMASK,R1 + LSLS R1,R0,#+16 + LSRS R1,R1,#+24 // Extract CFBP[15:8] => BASEPRI + MSR BASEPRI,R1 + LSLS R1,R0,#+8 // Extract CFBP[23:16] => FAULTMASK + LSRS R1,R1,#+24 + MSR FAULTMASK,R1 + LSRS R1,R0,#+24 // Extract CFBP[31:24] => CONTROL + LSRS R0,R1,#2 // Current CONTROL[1] -> Carry + ITE CS // Update saved CONTROL.SPSEL (CONTROL[1]). CONTROL.SPSEL is saved to LR[2] on exception entry => ARM DDI0403D, B1.5.6 Exception entry behavior + ORRCS LR,LR,#+4 + BICCC LR,LR,#+4 + BIC R1,R1,#+2 // CONTROL.SPSEL (CONTROL[1]) == 0 inside monitor. Otherwise behavior is UNPREDICTABLE + LSRS R0,R1,#+3 // New CONTROL.FPCA (CONTROL[2]) -> Carry + ITE CS // CONTROL[2] == FPCA => NOT(FPCA) saved to LR[4]. LR[4] == 0 => Extended stack frame, so FPU regs possibly on stack + BICCS LR,LR,#+0x10 // Remember: NOT(FPCA) is stored to LR. == 0 means: Extended stack frame + ORRCC LR,LR,#+0x10 + MRS R0,CONTROL + LSRS R0,R0,#+3 // CONTROL[2] -> Carry + ITE CS // Preserve original value of current CONTROL[2] + ORRCS R1,R1,#+0x04 + BICCC R1,R1,#+0x04 + MSR CONTROL,R1 + ISB // Necessary after writing to CONTROL, see ARM DDI0403D, B1.4.4 The special-purpose CONTROL register + B.N _HandleWriteRegDone +_HandleWriteRegFPU: +#if _HAS_FPU_REGS + CMP R1,#+53 // if (RegIndex < 53) { (20 (FPSCR), 21-52 FPS0-FPS31) + BCS _HandleWriteRegDone_Veneer + /* + Read Coprocessor Access Control Register (CPACR) to check if CP10 and CP11 are enabled + If not, access to floating point is not possible + CPACR[21:20] == CP10 enable. 0b01 = Privileged access only. 0b11 = Full access. Other = reserved + CPACR[23:22] == CP11 enable. 0b01 = Privileged access only. 0b11 = Full access. Other = reserved + */ + MOV R12,R0 // Save register data + LDR R0,_AddrCPACR + LDR R0,[R0] + LSLS R0,R0,#+8 + LSRS R0,R0,#+28 + CMP R0,#+0xF + BEQ _HandleWriteRegFPU_Allowed + CMP R0,#+0x5 + BNE _HandleWriteRegDone_Veneer +_HandleWriteRegFPU_Allowed: + CMP R1,#+21 // if (RegIndex < 21) (20 == FPSCR) + BCS _HandleWriteRegFPS0_FPS31 + LSRS R0,LR,#+5 // CONTROL[2] == FPCA => NOT(FPCA) saved to LR[4]. LR[4] == 0 => Extended stack frame, so FPU regs possibly on stack + BCS _HandleWriteFPSCRLazyMode // Remember: NOT(FPCA) is stored to LR. == 0 means: Extended stack frame + LDR R0,=_SYSTEM_FPCCR + LDR R0,[R0] + LSLS R0,R0,#+2 // FPCCR[30] -> Carry == 1 indicates if lazy mode is active, so space on stack is reserved but FPU registers are not saved on stack + BCS _HandleWriteFPSCRLazyMode + STR R12,[R2, #+_APP_SP_OFF_FPSCR] + B _HandleWriteRegDone +_HandleWriteFPSCRLazyMode: + VMSR FPSCR,R12 + B _HandleWriteRegDone +_HandleWriteRegFPS0_FPS31: // RegIndex == 21-52 + LDR R0,=_SYSTEM_FPCCR + LDR R0,[R0] + LSLS R0,R0,#+2 // FPCCR[30] -> Carry == 1 indicates if lazy mode is active, so space on stack is reserved but FPU registers are not saved on stack + BCS _HandleWriteFPS0_FPS31LazyMode + LSRS R0,LR,#+5 // CONTROL[2] == FPCA => NOT(FPCA) saved to LR[4]. LR[4] == 0 => Extended stack frame, so FPU regs possibly on stack + BCS _HandleWriteFPS0_FPS31LazyMode // Remember: NOT(FPCA) is stored to LR. == 0 means: Extended stack frame + SUBS R1,#+21 // Convert absolute reg index into rel. one + LSLS R1,R1,#+2 // RegIndex to position on stack + ADDS R1,#+_APP_SP_OFF_S0 + STR R12,[R2, R1] +_HandleWriteRegDone_Veneer: + B _HandleWriteRegDone +_HandleWriteFPS0_FPS31LazyMode: + SUBS R1,#+20 // Convert abs. RegIndex into rel. one + MOVS R0,#+6 + MULS R1,R0,R1 + LDR R0,=_HandleReadRegUnknown + SUB R0,R0,R1 // _HandleReadRegUnknown - 6 * ((RegIndex - 21) + 1) + ORR R0,R0,#1 // Thumb bit needs to be set in DestAddr + BX R0 + // + // Table for reading FPS0-FPS31 + // + VMOV S31,R12 // v = FPSx + B _HandleWriteRegDone + VMOV S30,R12 + B _HandleWriteRegDone + VMOV S29,R12 + B _HandleWriteRegDone + VMOV S28,R12 + B _HandleWriteRegDone + VMOV S27,R12 + B _HandleWriteRegDone + VMOV S26,R12 + B _HandleWriteRegDone + VMOV S25,R12 + B _HandleWriteRegDone + VMOV S24,R12 + B _HandleWriteRegDone + VMOV S23,R12 + B _HandleWriteRegDone + VMOV S22,R12 + B _HandleWriteRegDone + VMOV S21,R12 + B _HandleWriteRegDone + VMOV S20,R12 + B _HandleWriteRegDone + VMOV S19,R12 + B _HandleWriteRegDone + VMOV S18,R12 + B _HandleWriteRegDone + VMOV S17,R12 + B _HandleWriteRegDone + VMOV S16,R12 + B _HandleWriteRegDone + VMOV S15,R12 + B _HandleWriteRegDone + VMOV S14,R12 + B _HandleWriteRegDone + VMOV S13,R12 + B _HandleWriteRegDone + VMOV S12,R12 + B _HandleWriteRegDone + VMOV S11,R12 + B _HandleWriteRegDone + VMOV S10,R12 + B _HandleWriteRegDone + VMOV S9,R12 + B _HandleWriteRegDone + VMOV S8,R12 + B _HandleWriteRegDone + VMOV S7,R12 + B _HandleWriteRegDone + VMOV S6,R12 + B _HandleWriteRegDone + VMOV S5,R12 + B _HandleWriteRegDone + VMOV S4,R12 + B _HandleWriteRegDone + VMOV S3,R12 + B _HandleWriteRegDone + VMOV S2,R12 + B _HandleWriteRegDone + VMOV S1,R12 + B _HandleWriteRegDone + VMOV S0,R12 + B _HandleWriteRegDone +#else + B _HandleWriteRegUnknown +#endif +_HandleWriteRegUnknown: + B.N _HandleWriteRegDone +_HandleWriteRegDone: + B _IndicateMonReady // Indicate that monitor has read data, processed command and is ready for a new one + .end +/****** End Of File *************************************************/ From 6d6ed55ed7a91a7a64846b8be09a05dfa4c837e6 Mon Sep 17 00:00:00 2001 From: Tom Fifield Date: Sat, 5 Oct 2024 18:25:14 +0800 Subject: [PATCH 59/88] Retire PPR Boards (#4956) The Othernet project appears to have failed. Retire these boards/variants. --- boards/ppr.json | 47 --------- boards/ppr1.json | 47 --------- variants/ppr/platformio.ini | 8 -- variants/ppr/variant.cpp | 42 -------- variants/ppr/variant.h | 159 ------------------------------- variants/ppr1/platformio.ini | 9 -- variants/ppr1/variant.cpp | 41 -------- variants/ppr1/variant.h | 179 ----------------------------------- 8 files changed, 532 deletions(-) delete mode 100644 boards/ppr.json delete mode 100644 boards/ppr1.json delete mode 100644 variants/ppr/platformio.ini delete mode 100644 variants/ppr/variant.cpp delete mode 100644 variants/ppr/variant.h delete mode 100644 variants/ppr1/platformio.ini delete mode 100644 variants/ppr1/variant.cpp delete mode 100644 variants/ppr1/variant.h diff --git a/boards/ppr.json b/boards/ppr.json deleted file mode 100644 index 15e3025c0..000000000 --- a/boards/ppr.json +++ /dev/null @@ -1,47 +0,0 @@ -{ - "build": { - "arduino": { - "ldscript": "nrf52840_s140_v6.ld" - }, - "core": "nRF5", - "cpu": "cortex-m4", - "extra_flags": "-DARDUINO_NRF52840_PPR -DNRF52840_XXAA", - "f_cpu": "64000000L", - "hwids": [["0x239A", "0x4403"]], - "usb_product": "PPR", - "mcu": "nrf52840", - "variant": "ppr", - "variants_dir": "variants", - "bsp": { - "name": "adafruit" - }, - "softdevice": { - "sd_flags": "-DS140", - "sd_name": "s140", - "sd_version": "6.1.1", - "sd_fwid": "0x00B6" - }, - "bootloader": { - "settings_addr": "0xFF000" - } - }, - "connectivity": ["bluetooth"], - "debug": { - "jlink_device": "nRF52840_xxAA", - "onboard_tools": ["jlink"], - "svd_path": "nrf52840.svd", - "openocd_target": "nrf52840-mdk-rs" - }, - "frameworks": ["arduino"], - "name": "Meshtastic PPR (Adafruit BSP)", - "upload": { - "maximum_ram_size": 248832, - "maximum_size": 815104, - "require_upload_port": true, - "speed": 115200, - "protocol": "jlink", - "protocols": ["jlink", "nrfjprog", "stlink"] - }, - "url": "https://meshtastic.org/", - "vendor": "Othernet" -} diff --git a/boards/ppr1.json b/boards/ppr1.json deleted file mode 100644 index 35bf7d1e4..000000000 --- a/boards/ppr1.json +++ /dev/null @@ -1,47 +0,0 @@ -{ - "build": { - "arduino": { - "ldscript": "nrf52833_s113_v7.ld" - }, - "core": "nRF5", - "cpu": "cortex-m4", - "extra_flags": "-DARDUINO_NRF52833_PPR -DNRF52833_XXAA", - "f_cpu": "64000000L", - "hwids": [["0x239A", "0x4406"]], - "usb_product": "PPR", - "mcu": "nrf52833", - "variant": "ppr", - "variants_dir": "variants", - "bsp": { - "name": "adafruit" - }, - "softdevice": { - "sd_flags": "-DS113", - "sd_name": "s113", - "sd_version": "7.2.0", - "sd_fwid": "0x00b6" - }, - "bootloader": { - "settings_addr": "0xFF000" - } - }, - "connectivity": ["bluetooth"], - "debug": { - "jlink_device": "nRF52833_xxAA", - "onboard_tools": ["jlink"], - "svd_path": "nrf52833.svd", - "openocd_target": "nrf52840-mdk-rs" - }, - "frameworks": ["arduino"], - "name": "Meshtastic PPR1 (Adafruit BSP)", - "upload": { - "maximum_ram_size": 248832, - "maximum_size": 815104, - "require_upload_port": true, - "speed": 115200, - "protocol": "jlink", - "protocols": ["jlink", "nrfjprog", "stlink"] - }, - "url": "https://meshtastic.org/", - "vendor": "Othernet" -} diff --git a/variants/ppr/platformio.ini b/variants/ppr/platformio.ini deleted file mode 100644 index 22273ce8e..000000000 --- a/variants/ppr/platformio.ini +++ /dev/null @@ -1,8 +0,0 @@ -; The PPR board -[env:ppr] -extends = nrf52_base -board = ppr -board_level = extra -lib_deps = - ${arduino_base.lib_deps} - industruino/UC1701@^1.1.0 \ No newline at end of file diff --git a/variants/ppr/variant.cpp b/variants/ppr/variant.cpp deleted file mode 100644 index f5f219e9b..000000000 --- a/variants/ppr/variant.cpp +++ /dev/null @@ -1,42 +0,0 @@ -/* - Copyright (c) 2014-2015 Arduino LLC. All right reserved. - Copyright (c) 2016 Sandeep Mistry All right reserved. - Copyright (c) 2018, Adafruit Industries (adafruit.com) - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - See the GNU Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#include "variant.h" -#include "nrf.h" -#include "wiring_constants.h" -#include "wiring_digital.h" - -const uint32_t g_ADigitalPinMap[] = { - // P0 - 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 0xff, 12, 13, 0xff, 15, 0xff, 17, 18, 0xff, 20, 0xff, 22, 0xff, 24, 0xff, 26, 0xff, 28, 29, - 30, 31, - - // P1 - 32, 0xff, 34, 0xff, 36, 0xff, 38, 0xff, 0xff, 41, 42, 43, 0xff, 45}; - -void initVariant() -{ - // LED1 & LED2 - pinMode(PIN_LED1, OUTPUT); - ledOff(PIN_LED1); - - pinMode(PIN_LED2, OUTPUT); - ledOff(PIN_LED2); -} diff --git a/variants/ppr/variant.h b/variants/ppr/variant.h deleted file mode 100644 index 4c6cc015c..000000000 --- a/variants/ppr/variant.h +++ /dev/null @@ -1,159 +0,0 @@ -/* - Copyright (c) 2014-2015 Arduino LLC. All right reserved. - Copyright (c) 2016 Sandeep Mistry All right reserved. - Copyright (c) 2018, Adafruit Industries (adafruit.com) - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - See the GNU Lesser General Public License for more details. - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#pragma once - -/** Master clock frequency */ -#define VARIANT_MCK (64000000ul) - -// This board does not have a 32khz crystal -// #define USE_LFXO // Board uses 32khz crystal for LF -#define USE_LFRC // Board uses RC for LF - -/*---------------------------------------------------------------------------- - * Headers - *----------------------------------------------------------------------------*/ - -#include "WVariant.h" - -#ifdef __cplusplus -extern "C" { -#endif // __cplusplus - -// Number of pins defined in PinDescription array -#define PINS_COUNT (46) -#define NUM_DIGITAL_PINS (46) -#define NUM_ANALOG_INPUTS (0) -#define NUM_ANALOG_OUTPUTS (0) - -// LEDs -#define PIN_LED1 (0) -#define PIN_LED2 (1) - -#define LED_BUILTIN PIN_LED1 -#define LED_CONN PIN_LED2 - -#define LED_RED PIN_LED1 -#define LED_GREEN PIN_LED2 - -// FIXME, bluefruit automatically blinks this led while connected. call AdafruitBluefruit::autoConnLed to change this. -#define LED_BLUE LED_GREEN - -#define LED_STATE_ON 1 // State when LED is litted - -/* - * Buttons - */ -#define PIN_BUTTON1 4 // center -#define PIN_BUTTON2 2 -#define PIN_BUTTON3 3 -#define PIN_BUTTON4 5 -#define PIN_BUTTON5 6 - -/* - * Analog pins - */ -#define PIN_A0 (0xff) -#define PIN_A1 (0xff) -#define PIN_A2 (0xff) -#define PIN_A3 (0xff) -#define PIN_A4 (0xff) -#define PIN_A5 (0xff) -#define PIN_A6 (0xff) -#define PIN_A7 (0xff) - -static const uint8_t A0 = PIN_A0; -static const uint8_t A1 = PIN_A1; -static const uint8_t A2 = PIN_A2; -static const uint8_t A3 = PIN_A3; -static const uint8_t A4 = PIN_A4; -static const uint8_t A5 = PIN_A5; -static const uint8_t A6 = PIN_A6; -static const uint8_t A7 = PIN_A7; -#define ADC_RESOLUTION 14 - -// Other pins -#define PIN_AREF (0xff) -// #define PIN_NFC1 (9) -// #define PIN_NFC2 (10) - -static const uint8_t AREF = PIN_AREF; - -/* - * Serial interfaces - */ - -// GPS is on Serial1 -#define PIN_SERIAL1_RX (8) -#define PIN_SERIAL1_TX (9) - -// Connected to Jlink CDC -// #define PIN_SERIAL2_RX (8) -// #define PIN_SERIAL2_TX (6) - -/* - * SPI Interfaces - */ -#define SPI_INTERFACES_COUNT 1 - -#define PIN_SPI_MISO (15) -#define PIN_SPI_MOSI (13) -#define PIN_SPI_SCK (12) - -// static const uint8_t SS = 44; -static const uint8_t MOSI = PIN_SPI_MOSI; -static const uint8_t MISO = PIN_SPI_MISO; -static const uint8_t SCK = PIN_SPI_SCK; - -/* - * Wire Interfaces - */ -#define WIRE_INTERFACES_COUNT 1 - -#define PIN_WIRE_SDA (32 + 2) -#define PIN_WIRE_SCL (32) - -// CUSTOM GPIOs the SX1262 -#define USE_SX1262 -#define SX126X_CS (10) -#define SX126X_DIO1 (20) -#define SX1262_DIO2 (26) -#define SX126X_BUSY (31) // Supposed to be P0.18 but because of reworks, now on P0.31 (18) -#define SX126X_RESET (17) -// #define SX126X_ANT_SW (32 + 10) -#define SX126X_RXEN (22) -#define SX126X_TXEN (24) -// Indicates this SX1262 is inside of an ebyte E22 module and special config should be done for that -#define SX126X_DIO3_TCXO_VOLTAGE 1.8 - -// ERC12864-10 LCD -#define ERC12864_CS (32 + 4) -#define ERC12864_RESET (32 + 6) -#define ERC12864_CD (32 + 9) - -// L80 GPS -#define L80_PPS (28) -#define L80_RESET (29) - -#ifdef __cplusplus -} -#endif - -/*---------------------------------------------------------------------------- - * Arduino objects - C++ only - *----------------------------------------------------------------------------*/ diff --git a/variants/ppr1/platformio.ini b/variants/ppr1/platformio.ini deleted file mode 100644 index f6c2a5e0b..000000000 --- a/variants/ppr1/platformio.ini +++ /dev/null @@ -1,9 +0,0 @@ -; The PPR board -[env:ppr1] -extends = nrf52_base -board = ppr1 -board_level = extra -build_flags = ${nrf52_base.build_flags} -Ivariants/ppr1 -build_src_filter = ${nrf52_base.build_src_filter} +<../variants/ppr1> -lib_deps = - ${arduino_base.lib_deps} \ No newline at end of file diff --git a/variants/ppr1/variant.cpp b/variants/ppr1/variant.cpp deleted file mode 100644 index acc3e344a..000000000 --- a/variants/ppr1/variant.cpp +++ /dev/null @@ -1,41 +0,0 @@ -/* - Copyright (c) 2014-2015 Arduino LLC. All right reserved. - Copyright (c) 2016 Sandeep Mistry All right reserved. - Copyright (c) 2018, Adafruit Industries (adafruit.com) - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - See the GNU Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#include "variant.h" -#include "nrf.h" -#include "wiring_constants.h" -#include "wiring_digital.h" - -const uint32_t g_ADigitalPinMap[] = { - // P0 - 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, - - // P1 - 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45}; - -void initVariant() -{ - // LED1 & LED2 - pinMode(PIN_LED1, OUTPUT); - ledOff(PIN_LED1); - - pinMode(PIN_LED2, OUTPUT); - ledOff(PIN_LED2); -} diff --git a/variants/ppr1/variant.h b/variants/ppr1/variant.h deleted file mode 100644 index ba3a25c2a..000000000 --- a/variants/ppr1/variant.h +++ /dev/null @@ -1,179 +0,0 @@ -/* - Copyright (c) 2014-2015 Arduino LLC. All right reserved. - Copyright (c) 2016 Sandeep Mistry All right reserved. - Copyright (c) 2018, Adafruit Industries (adafruit.com) - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - See the GNU Lesser General Public License for more details. - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#pragma once - -/** Master clock frequency */ -#define VARIANT_MCK (64000000ul) - -// This board does have a 32khz crystal -#define USE_LFXO // Board uses 32khz crystal for LF -// #define USE_LFRC // Board uses RC for LF - -/*---------------------------------------------------------------------------- - * Headers - *----------------------------------------------------------------------------*/ - -#include "WVariant.h" - -#ifdef __cplusplus -extern "C" { -#endif // __cplusplus - -// Number of pins defined in PinDescription array -#define PINS_COUNT (46) -#define NUM_DIGITAL_PINS (46) -#define NUM_ANALOG_INPUTS (0) -#define NUM_ANALOG_OUTPUTS (0) - -// LEDs -#define PIN_LED1 (25) -#define PIN_LED2 (11) - -#define LED_BUILTIN PIN_LED1 -#define LED_CONN PIN_LED2 - -#define LED_RED PIN_LED1 -#define LED_GREEN PIN_LED2 - -// FIXME, bluefruit automatically blinks this led while connected. call AdafruitBluefruit::autoConnLed to change this. -#define LED_BLUE LED_GREEN - -#define LED_STATE_ON 1 // State when LED is litted - -/* - * Buttons - */ -#define PIN_BUTTON1 4 // up -#define PIN_BUTTON2 2 // left -#define PIN_BUTTON3 3 // center -#define PIN_BUTTON4 5 // right -#define PIN_BUTTON5 6 // down - -/* - * Analog pins - */ -#define PIN_A0 (0xff) -#define PIN_A1 (0xff) -#define PIN_A2 (0xff) -#define PIN_A3 (0xff) -#define PIN_A4 (0xff) -#define PIN_A5 (0xff) -#define PIN_A6 (0xff) -#define PIN_A7 (0xff) - -static const uint8_t A0 = PIN_A0; -static const uint8_t A1 = PIN_A1; -static const uint8_t A2 = PIN_A2; -static const uint8_t A3 = PIN_A3; -static const uint8_t A4 = PIN_A4; -static const uint8_t A5 = PIN_A5; -static const uint8_t A6 = PIN_A6; -static const uint8_t A7 = PIN_A7; -#define ADC_RESOLUTION 14 - -// Other pins -#define PIN_AREF (0xff) -// #define PIN_NFC1 (9) -// #define PIN_NFC2 (10) - -static const uint8_t AREF = PIN_AREF; - -/* - * Serial interfaces - */ - -// GPS is on Serial1 -#define PIN_SERIAL1_RX (8) -#define PIN_SERIAL1_TX (9) - -// We intentionally leave this undefined so we don't even try to make a Ublox driver -// #define GPS_TX_PIN PIN_SERIAL1_TX -// #define GPS_RX_PIN PIN_SERIAL1_RX - -#define PIN_GPS_RESET 29 // active high -#define PIN_GPS_PPS 28 -// #define PIN_GPS_WAKE 20 // CELL_CTRL in schematic? based on their example code -#define PIN_GPS_EN 7 // GPS_EN active high - -// #define PIN_VUSB_EN 21 - -// LCD - -#define PIN_LCD_RESET 23 // active low, pulse low for 20ms at boot -#define USE_ST7567 - -/// Charge controller I2C address -#define BQ25703A_ADDR 0x6b - -// Define if screen should be mirrored left to right -#define SCREEN_MIRROR - -// LCD screens are slow, so slowdown the wipe so it looks better -#define SCREEN_TRANSITION_FRAMERATE 10 // fps - -/* - * SPI Interfaces - */ -#define SPI_INTERFACES_COUNT 1 - -#define PIN_SPI_MISO (15) -#define PIN_SPI_MOSI (13) -#define PIN_SPI_SCK (12) - -// static const uint8_t SS = 44; -static const uint8_t MOSI = PIN_SPI_MOSI; -static const uint8_t MISO = PIN_SPI_MISO; -static const uint8_t SCK = PIN_SPI_SCK; - -/* - * Wire Interfaces - */ -#define WIRE_INTERFACES_COUNT 1 - -#define PIN_WIRE_SDA (32 + 2) -#define PIN_WIRE_SCL (32) - -// CUSTOM GPIOs the SX1262 -#define USE_SX1262 -#define SX126X_CS (0 + 10) // FIXME - we really should define LORA_CS instead -#define SX126X_DIO1 (0 + 20) -#define SX1262_DIO2 (0 + 26) -#define SX126X_BUSY (0 + 19) -#define SX126X_RESET (0 + 17) -#define SX126X_TXEN (0 + 24) -#define SX126X_RXEN (0 + 22) -// Not really an E22 but this board clones using DIO3 for tcxo control -#define SX126X_DIO3_TCXO_VOLTAGE 1.8 - -// FIXME, to prevent burning out parts I've set the power level super low, because I don't have -// an antenna wired up -#define SX126X_MAX_POWER 1 - -#define LORA_DISABLE_SENDING // Define this to disable transmission for testing (power testing etc...) - -// To debug via the segger JLINK console rather than the CDC-ACM serial device -// #define USE_SEGGER - -#ifdef __cplusplus -} -#endif - -/*---------------------------------------------------------------------------- - * Arduino objects - C++ only - *----------------------------------------------------------------------------*/ From 243421b2a5ca2641b40440580bf81a59c9aa7955 Mon Sep 17 00:00:00 2001 From: Tom Fifield Date: Sat, 5 Oct 2024 18:25:28 +0800 Subject: [PATCH 60/88] Retire lora-relay boards (#4957) The lora-relay boards were important pathfinders for nrf52 support some years back. They are no longer commonly produced and there are now many nrf52 options on the market. Retire these boards and associated variant. --- boards/lora-relay-v1.json | 47 ------- boards/lora-relay-v2.json | 47 ------- platformio.ini | 3 +- variants/lora_relay_v1/platformio.ini | 24 ---- variants/lora_relay_v1/variant.cpp | 105 -------------- variants/lora_relay_v1/variant.h | 161 ---------------------- variants/lora_relay_v2/platformio.ini | 26 ---- variants/lora_relay_v2/variant.cpp | 105 -------------- variants/lora_relay_v2/variant.h | 188 -------------------------- 9 files changed, 1 insertion(+), 705 deletions(-) delete mode 100644 boards/lora-relay-v1.json delete mode 100644 boards/lora-relay-v2.json delete mode 100644 variants/lora_relay_v1/platformio.ini delete mode 100644 variants/lora_relay_v1/variant.cpp delete mode 100644 variants/lora_relay_v1/variant.h delete mode 100644 variants/lora_relay_v2/platformio.ini delete mode 100644 variants/lora_relay_v2/variant.cpp delete mode 100644 variants/lora_relay_v2/variant.h diff --git a/boards/lora-relay-v1.json b/boards/lora-relay-v1.json deleted file mode 100644 index b390b8404..000000000 --- a/boards/lora-relay-v1.json +++ /dev/null @@ -1,47 +0,0 @@ -{ - "build": { - "arduino": { - "ldscript": "nrf52840_s140_v6.ld" - }, - "core": "nRF5", - "cpu": "cortex-m4", - "extra_flags": "-DARDUINO_NRF52840_LORA_RELAY_V1 -DNRF52840_XXAA", - "f_cpu": "64000000L", - "hwids": [["0x239A", "0x4404"]], - "usb_product": "LORA_RELAY", - "mcu": "nrf52840", - "variant": "lora_relay_v1", - "variants_dir": "variants", - "bsp": { - "name": "adafruit" - }, - "softdevice": { - "sd_flags": "-DS140", - "sd_name": "s140", - "sd_version": "6.1.1", - "sd_fwid": "0x00B6" - }, - "bootloader": { - "settings_addr": "0xFF000" - } - }, - "connectivity": ["bluetooth"], - "debug": { - "jlink_device": "nRF52840_xxAA", - "onboard_tools": ["jlink"], - "svd_path": "nrf52840.svd", - "openocd_target": "nrf52840-mdk-rs" - }, - "frameworks": ["arduino"], - "name": "Meshtastic Lora Relay V1 (Adafruit BSP)", - "upload": { - "maximum_ram_size": 248832, - "maximum_size": 815104, - "require_upload_port": true, - "speed": 115200, - "protocol": "jlink", - "protocols": ["jlink", "nrfjprog", "stlink"] - }, - "url": "https://github.com/BigCorvus/SX1262-LoRa-BLE-Relay", - "vendor": "BigCorvus" -} diff --git a/boards/lora-relay-v2.json b/boards/lora-relay-v2.json deleted file mode 100644 index 52b775e58..000000000 --- a/boards/lora-relay-v2.json +++ /dev/null @@ -1,47 +0,0 @@ -{ - "build": { - "arduino": { - "ldscript": "nrf52840_s140_v6.ld" - }, - "core": "nRF5", - "cpu": "cortex-m4", - "extra_flags": "-DARDUINO_NRF52840_LORA_RELAY_V2 -DNRF52840_XXAA", - "f_cpu": "64000000L", - "hwids": [["0x239A", "0x4406"]], - "usb_product": "LORA_RELAY", - "mcu": "nrf52840", - "variant": "lora_relay_v2", - "variants_dir": "variants", - "bsp": { - "name": "adafruit" - }, - "softdevice": { - "sd_flags": "-DS140", - "sd_name": "s140", - "sd_version": "6.1.1", - "sd_fwid": "0x00B6" - }, - "bootloader": { - "settings_addr": "0xFF000" - } - }, - "connectivity": ["bluetooth"], - "debug": { - "jlink_device": "nRF52840_xxAA", - "onboard_tools": ["jlink"], - "svd_path": "nrf52840.svd", - "openocd_target": "nrf52840-mdk-rs" - }, - "frameworks": ["arduino"], - "name": "Meshtastic Lora Relay V1 (Adafruit BSP)", - "upload": { - "maximum_ram_size": 248832, - "maximum_size": 815104, - "require_upload_port": true, - "speed": 115200, - "protocol": "jlink", - "protocols": ["jlink", "nrfjprog", "stlink"] - }, - "url": "https://github.com/BigCorvus/SX1262-LoRa-BLE-Relay", - "vendor": "BigCorvus" -} diff --git a/platformio.ini b/platformio.ini index 22e2b6259..d4cd89631 100644 --- a/platformio.ini +++ b/platformio.ini @@ -17,11 +17,10 @@ default_envs = tbeam ;default_envs = tlora-v2-1-1_6 ;default_envs = tlora-v2-1-1_6-tcxo ;default_envs = tlora-t3s3-v1 -;default_envs = lora-relay-v1 # nrf board ;default_envs = t-echo ;default_envs = canaryone ;default_envs = nrf52840dk-geeksville -;default_envs = native # lora-relay-v1 # nrf52840dk-geeksville # linux # or if you'd like to change the default to something like lora-relay-v1 put that here +;default_envs = native ;default_envs = nano-g1 ;default_envs = pca10059_diy_eink ;default_envs = meshtastic-diy-v1 diff --git a/variants/lora_relay_v1/platformio.ini b/variants/lora_relay_v1/platformio.ini deleted file mode 100644 index 435d256c5..000000000 --- a/variants/lora_relay_v1/platformio.ini +++ /dev/null @@ -1,24 +0,0 @@ -; The https://github.com/BigCorvus/SX1262-LoRa-BLE-Relay board by @BigCorvus -[env:lora-relay-v1] -extends = nrf52840_base -board = lora-relay-v1 -board_level = extra -# add our variants files to the include and src paths -# define build flags for the TFT_eSPI library -build_flags = ${nrf52840_base.build_flags} -Ivariants/lora_relay_v1 - -DUSER_SETUP_LOADED - -DTFT_WIDTH=80 - -DTFT_HEIGHT=160 - -DST7735_GREENTAB160x80 - -DST7735_DRIVER - -DTFT_CS=ST7735_CS - -DTFT_DC=ST7735_RS - -DTFT_RST=ST7735_RESET - -DSPI_FREQUENCY=27000000 - -L "${platformio.libdeps_dir}/${this.__env__}/bsec2/src/cortex-m4/fpv4-sp-d16-hard" -build_src_filter = ${nrf52_base.build_src_filter} +<../variants/lora_relay_v1> -lib_deps = - ${nrf52840_base.lib_deps} - sparkfun/SparkFun BQ27441 LiPo Fuel Gauge Arduino Library@^1.1.0 - bodmer/TFT_eSPI@^2.4.76 - adafruit/Adafruit NeoPixel @ ^1.12.0 \ No newline at end of file diff --git a/variants/lora_relay_v1/variant.cpp b/variants/lora_relay_v1/variant.cpp deleted file mode 100644 index 891c8bb29..000000000 --- a/variants/lora_relay_v1/variant.cpp +++ /dev/null @@ -1,105 +0,0 @@ -/* - Copyright (c) 2014-2015 Arduino LLC. All right reserved. - Copyright (c) 2016 Sandeep Mistry All right reserved. - Copyright (c) 2018, Adafruit Industries (adafruit.com) - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - See the GNU Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#include "variant.h" -#include "nrf.h" -#include "wiring_constants.h" -#include "wiring_digital.h" - -const uint32_t g_ADigitalPinMap[] = { - // D0 .. D13 - 25, // D0 is P0.25 (UART TX) - 24, // D1 is P0.24 (UART RX - 10, // D2 is P0.10 (NFC2) - 47, // D3 is P1.15 (LED1) - 42, // D4 is P1.10 (LED2) - 40, // D5 is P1.08 - 7, // D6 is P0.07 - 34, // D7 is P1.02 (Button) - 16, // D8 is P0.16 (NeoPixel) - 26, // D9 is P0.26 D_RS (IPS data/command control) - 27, // D10 is P0.27 - 6, // D11 is P0.06 D_RES (IPS display reset) - 8, // D12 is P0.08 D_CS (IPS display chip select) - 41, // D13 is P1.09 BLT (IPS display backlight) - 4, // D14 is P0.04 SX1262 RXEN - 5, // D15 is P0.05 BOOST_EN (5V buck converter enable for the the radio power) - - // D14 .. D21 (aka A0 .. A7) - 30, // D16 is P0.30 (A0) - 28, // D17 is P0.28 (A1) - 2, // D18 is P0.02 (A2) - 3, // D19 is P0.03 (A3) - 29, // D20 is P0.29 (A4, Battery) - 31, // D21 is P0.31 (A5, ARef) - - // D22 .. D23 (aka I2C pins) - 12, // D22 is P0.12 (SDA) - 11, // D23 is P0.11 (SCL) - - // D24 .. D26 (aka SPI pins) - 15, // D24 is P0.15 (SPI MISO) - 13, // D25 is P0.13 (SPI MOSI) - 14, // D26 is P0.14 (SPI SCK ) - - // QSPI pins (not exposed via any header / test point) - // 19, // P0.19 (QSPI CLK) - // 20, // P0.20 (QSPI CS) - // 17, // P0.17 (QSPI Data 0) - // 22, // P0.22 (QSPI Data 1) - // 23, // P0.23 (QSPI Data 2) - // 21, // P0.21 (QSPI Data 3) - - // The remaining NFC pin - 9, // D27 P0.09 (NFC1, exposed only via test point on bottom of board) - - // The following pins were never listed as they were considered unusable - // 0, // P0.00 is XL1 (attached to 32.768kHz crystal) Never expose as GPIOs - // 1, // P0.01 is XL2 (attached to 32.768kHz crystal) - 18, // D28 P0.18 is RESET (attached to switch) - // 32, // P1.00 is SWO (attached to debug header) - - // D29-D43 - 27, // D29 P0.27 E22-SX1262 DIO1 - 28, // D30 P0.28 E22-SX1262 DIO2 - 30, // D31 P0.30 E22-SX1262 TXEN - 35, // D32 P1.03 E22-SX1262 NSS - 32 + 8, // D33 P1.08 E22-SX1262 BUSY - 32 + 12, // D34 P1.12 E22-SX1262 RESET - 32 + 1, // P1.01 BTN_UP - 32 + 2, // P1.02 SWITCH - 32 + 14, // D37 P1.14 is not connected per schematic - 36, // P1.04 is not connected per schematic - 37, // P1.05 is not connected per schematic - 38, // P1.06 is not connected per schematic - 39, // P1.07 is not connected per schematic - 43, // P1.11 is not connected per schematic - 45, // P1.13 is not connected per schematic -}; - -void initVariant() -{ - // LED1 & LED2 - pinMode(PIN_LED1, OUTPUT); - ledOff(PIN_LED1); - - pinMode(PIN_LED2, OUTPUT); - ledOff(PIN_LED2); -} diff --git a/variants/lora_relay_v1/variant.h b/variants/lora_relay_v1/variant.h deleted file mode 100644 index 6efd711c6..000000000 --- a/variants/lora_relay_v1/variant.h +++ /dev/null @@ -1,161 +0,0 @@ -/* - Copyright (c) 2014-2015 Arduino LLC. All right reserved. - Copyright (c) 2016 Sandeep Mistry All right reserved. - Copyright (c) 2018, Adafruit Industries (adafruit.com) - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - See the GNU Lesser General Public License for more details. - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#ifndef _VARIANT_LORA_RELAY_V1_ -#define _VARIANT_LORA_RELAY_V1_ - -/** Master clock frequency */ -#define VARIANT_MCK (64000000ul) - -#define USE_LFXO // Board uses 32khz crystal for LF -// define USE_LFRC // Board uses RC for LF - -/*---------------------------------------------------------------------------- - * Headers - *----------------------------------------------------------------------------*/ - -#include "WVariant.h" - -#ifdef __cplusplus -extern "C" { -#endif // __cplusplus - -// Number of pins defined in PinDescription array -#define PINS_COUNT (43) -#define NUM_DIGITAL_PINS (43) -#define NUM_ANALOG_INPUTS (6) // A6 is used for battery, A7 is analog reference -#define NUM_ANALOG_OUTPUTS (0) - -// LEDs -#define PIN_LED1 (3) -#define PIN_LED2 (4) -// #define PIN_NEOPIXEL (8) -#define HAS_NEOPIXEL // Enable the use of neopixels -#define NEOPIXEL_COUNT 1 // How many neopixels are connected -#define NEOPIXEL_DATA 8 // gpio pin used to send data to the neopixels -#define NEOPIXEL_TYPE (NEO_GRB + NEO_KHZ800) // type of neopixels in use - -#define LED_BUILTIN PIN_LED1 -#define LED_CONN PIN_LED2 - -#define LED_RED PIN_LED1 -#define LED_BLUE PIN_LED2 - -#define LED_STATE_ON 1 // State when LED is litted - -/* - * Buttons - */ -#define PIN_BUTTON1 (7) - -/* - * Analog pins - */ -#define PIN_A0 (16) -#define PIN_A1 (17) -#define PIN_A2 (18) -#define PIN_A3 (19) -#define PIN_A4 (20) -#define PIN_A5 (21) - -static const uint8_t A0 = PIN_A0; -static const uint8_t A1 = PIN_A1; -static const uint8_t A2 = PIN_A2; -static const uint8_t A3 = PIN_A3; -static const uint8_t A4 = PIN_A4; -static const uint8_t A5 = PIN_A5; -#define ADC_RESOLUTION 14 - -// Other pins -#define PIN_AREF PIN_A5 -#define PIN_VBAT PIN_A4 -#define BATTERY_PIN PIN_VBAT -#define PIN_NFC1 (33) -#define PIN_NFC2 (2) -#define PIN_PIEZO (37) -static const uint8_t AREF = PIN_AREF; - -/* - * Serial interfaces - */ -#define PIN_SERIAL1_RX (1) -#define PIN_SERIAL1_TX (0) - -/* - * SPI Interfaces - */ -#define SPI_INTERFACES_COUNT 1 - -#define PIN_SPI_MISO (24) -#define PIN_SPI_MOSI (25) -#define PIN_SPI_SCK (26) - -static const uint8_t SS = (5); -static const uint8_t MOSI = PIN_SPI_MOSI; -static const uint8_t MISO = PIN_SPI_MISO; -static const uint8_t SCK = PIN_SPI_SCK; - -/* - * Wire Interfaces - */ -#define WIRE_INTERFACES_COUNT 1 - -#define PIN_WIRE_SDA (22) -#define PIN_WIRE_SCL (23) - -// I2C device addresses -#define I2C_ADDR_BQ27441 0x55 // Battery gauge - -// SX1262 declaration -#define USE_SX1262 - -// CUSTOM GPIOs the SX1262 -#define SX126X_CS (32) - -// If you would prefer to get console debug output over the JTAG ICE connection rather than the CDC-ACM USB serial device, just -// define this. #define USE_SEGGER - -#define SX126X_DIO1 (29) -#define SX1262_DIO2 (30) -#define SX126X_BUSY (33) // Supposed to be P0.18 but because of reworks, now on P0.31 (18) -#define SX126X_RESET (34) -// #define SX126X_ANT_SW (32 + 10) -#define SX126X_RXEN (14) -#define SX126X_TXEN (31) -#define SX126X_POWER_EN \ - (15) // FIXME, see warning hre https://github.com/BigCorvus/SX1262-LoRa-BLE-Relay/blob/master/LORA_RELAY_NRF52840.ino -// Indicates this SX1262 is inside of an ebyte E22 module and special config should be done for that -#define SX126X_DIO3_TCXO_VOLTAGE 1.8 - -#define ST7735_RESET (11) // Output -#define ST7735_CS (12) -#define TFT_BL (13) -#define ST7735_RS (9) - -// #define LORA_DISABLE_SENDING // The board can brownout during lora TX if you don't have a battery connected. Disable sending -// to allow USB power only based debugging - -#ifdef __cplusplus -} -#endif - -/*---------------------------------------------------------------------------- - * Arduino objects - C++ only - *----------------------------------------------------------------------------*/ - -#endif \ No newline at end of file diff --git a/variants/lora_relay_v2/platformio.ini b/variants/lora_relay_v2/platformio.ini deleted file mode 100644 index 3598466d5..000000000 --- a/variants/lora_relay_v2/platformio.ini +++ /dev/null @@ -1,26 +0,0 @@ -; The https://github.com/BigCorvus/LoRa-BLE-Relay-v2 board by @BigCorvus -[env:lora-relay-v2] -extends = nrf52840_base -board = lora-relay-v2 -board_level = extra -# add our variants files to the include and src paths -# define build flags for the TFT_eSPI library -build_flags = ${nrf52840_base.build_flags} -Ivariants/lora_relay_v2 - -DUSER_SETUP_LOADED - -DTFT_WIDTH=80 - -DTFT_HEIGHT=160 - -DST7735_GREENTAB160x80 - -DST7735_DRIVER - -DTFT_CS=ST7735_CS - -DTFT_DC=ST7735_RS - -DTFT_RST=ST7735_RESET - -DSPI_FREQUENCY=27000000 - -DTFT_WR=ST7735_SDA - -DTFT_SCLK=ST7735_SCK - -L "${platformio.libdeps_dir}/${this.__env__}/bsec2/src/cortex-m4/fpv4-sp-d16-hard" -build_src_filter = ${nrf52_base.build_src_filter} +<../variants/lora_relay_v2> -lib_deps = - ${nrf52840_base.lib_deps} - sparkfun/SparkFun BQ27441 LiPo Fuel Gauge Arduino Library@^1.1.0 - bodmer/TFT_eSPI@^2.4.76 - adafruit/Adafruit NeoPixel @ ^1.12.0 \ No newline at end of file diff --git a/variants/lora_relay_v2/variant.cpp b/variants/lora_relay_v2/variant.cpp deleted file mode 100644 index 23d648873..000000000 --- a/variants/lora_relay_v2/variant.cpp +++ /dev/null @@ -1,105 +0,0 @@ -/* - Copyright (c) 2014-2015 Arduino LLC. All right reserved. - Copyright (c) 2016 Sandeep Mistry All right reserved. - Copyright (c) 2018, Adafruit Industries (adafruit.com) - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - See the GNU Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#include "variant.h" -#include "nrf.h" -#include "wiring_constants.h" -#include "wiring_digital.h" - -const uint32_t g_ADigitalPinMap[] = { - // D0 .. D13 - 25, // D0 is P0.25 (UART TX) - 24, // D1 is P0.24 (UART RX - 10, // D2 is P0.10 (NFC2) - 47, // D3 is P1.15 (LED1) - (32 + 10), // D4 is P1.10 (LED2) - 40, // D5 is P1.08 - 7, // D6 is P0.07 - 34, // D7 is P1.02 (Switch) - 16, // D8 is P0.16 (NeoPixel) - 26, // D9 is P0.26 D_RS (IPS data/command control) - 27, // D10 is P0.27 - 6, // D11 is P0.06 D_RES (IPS display reset) - 8, // D12 is P0.08 D_CS (IPS display chip select) - 41, // D13 is P0.23 BLT (IPS display backlight) - 4, // D14 is P0.04 SX1262 RXEN - 5, // D15 is P0.05 BOOST_EN (5V buck converter enable for the the radio power) - - // D14 .. D21 (aka A0 .. A7) - 30, // D16 is P0.30 (A0) - 28, // D17 is P0.28 (A1) - 2, // D18 is P0.02 (A2) - 3, // D19 is P0.03 (A3) - 29, // D20 is P0.29 (A4, Battery) - 31, // D21 is P0.31 (A5, ARef) - - // D22 .. D23 (aka I2C pins) - 12, // D22 is P0.12 (SDA) - 11, // D23 is P0.11 (SCL) - - // D24 .. D26 (aka SPI pins) - 15, // D24 is P0.15 (SPI MISO) - 13, // D25 is P0.13 (SPI MOSI) - 14, // D26 is P0.14 (SPI SCK ) - - // QSPI pins (not exposed via any header / test point) - // 19, // P0.19 (QSPI CLK) - // 20, // P0.20 (QSPI CS) - // 17, // P0.17 (QSPI Data 0) - // 22, // P0.22 (QSPI Data 1) - // 23, // P0.23 (QSPI Data 2) - // 21, // P0.21 (QSPI Data 3) - - // The remaining NFC pin - 9, // D27 P0.09 (NFC1, exposed only via test point on bottom of board) - - // The following pins were never listed as they were considered unusable - // 0, // P0.00 is XL1 (attached to 32.768kHz crystal) Never expose as GPIOs - // 1, // P0.01 is XL2 (attached to 32.768kHz crystal) - 18, // D28 P0.18 is RESET (attached to switch) - // 32, // P1.00 is SWO (attached to debug header) - - // D29-D43 - 32 + 12, // D29 P0.27 E22-SX1262 DIO1 - 28, // D30 P0.28 E22-SX1262 DIO2 - 30, // D31 P0.30 E22-SX1262 TXEN - 35, // D32 P1.03 E22-SX1262 NSS - 32 + 8, // D33 P1.08 E22-SX1262 BUSY - 27, // D34 P0.27 E22-SX1262 RESET - 32 + 1, // D35 P1.01 BTN_UP - 32, // D36 P1.0 GPS power - 21, // D37 P0.21 disp_clk - 36, // P1.04 BTN_OK - 37, // D39 P0.19 disp_SDA - 38, // D40 P1.06 BUZZER - 39, // P1.07 is not connected per schematic - 43, // P1.11 is not connected per schematic - 45, // P1.13 is not connected per schematic -}; - -void initVariant() -{ - // LED1 & LED2 - pinMode(PIN_LED1, OUTPUT); - ledOff(PIN_LED1); - - pinMode(PIN_LED2, OUTPUT); - ledOff(PIN_LED2); -} diff --git a/variants/lora_relay_v2/variant.h b/variants/lora_relay_v2/variant.h deleted file mode 100644 index f18f81034..000000000 --- a/variants/lora_relay_v2/variant.h +++ /dev/null @@ -1,188 +0,0 @@ -/* - Copyright (c) 2014-2015 Arduino LLC. All right reserved. - Copyright (c) 2016 Sandeep Mistry All right reserved. - Copyright (c) 2018, Adafruit Industries (adafruit.com) - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - See the GNU Lesser General Public License for more details. - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#ifndef _VARIANT_LORA_RELAY_V1_ -#define _VARIANT_LORA_RELAY_V1_ - -/** Master clock frequency */ -#define VARIANT_MCK (64000000ul) - -#define USE_LFXO // Board uses 32khz crystal for LF -// define USE_LFRC // Board uses RC for LF - -/* -kevinh todo - -ok leds -ok buttons -ok gps power -ok gps signal -ok? lcd -ok buzzer -serial flash -ok lora (inc boost en) - -mention dat1 and dat2 on sd card -use hardware spi controller for lcd - not bitbang - -*/ - -/*---------------------------------------------------------------------------- - * Headers - *----------------------------------------------------------------------------*/ - -#include "WVariant.h" - -#ifdef __cplusplus -extern "C" { -#endif // __cplusplus - -// Number of pins defined in PinDescription array -#define PINS_COUNT (43) -#define NUM_DIGITAL_PINS (43) -#define NUM_ANALOG_INPUTS (6) // A6 is used for battery, A7 is analog reference -#define NUM_ANALOG_OUTPUTS (0) - -// LEDs -#define PIN_LED1 (3) -#define PIN_LED2 (4) -// #define PIN_NEOPIXEL (8) -#define HAS_NEOPIXEL // Enable the use of neopixels -#define NEOPIXEL_COUNT 1 // How many neopixels are connected -#define NEOPIXEL_DATA 8 // gpio pin used to send data to the neopixels -#define NEOPIXEL_TYPE (NEO_GRB + NEO_KHZ800) // type of neopixels in use - -#define PIN_BUZZER (40) - -#define LED_BUILTIN PIN_LED1 -#define LED_CONN PIN_LED2 - -#define LED_RED PIN_LED1 -#define LED_BLUE PIN_LED2 - -#define LED_STATE_ON 1 // State when LED is litted - -/* - * Buttons - */ -#define PIN_BUTTON1 (7) -#define PIN_BUTTON2 (35) -#define PIN_BUTTON3 (37) - -/* - * Analog pins - */ -#define PIN_A0 (16) -#define PIN_A1 (17) -#define PIN_A2 (18) -#define PIN_A3 (19) -#define PIN_A4 (20) -#define PIN_A5 (21) - -static const uint8_t A0 = PIN_A0; -static const uint8_t A1 = PIN_A1; -static const uint8_t A2 = PIN_A2; -static const uint8_t A3 = PIN_A3; -static const uint8_t A4 = PIN_A4; -static const uint8_t A5 = PIN_A5; -#define ADC_RESOLUTION 14 - -// Other pins -#define PIN_AREF PIN_A5 -#define PIN_VBAT PIN_A4 -#define BATTERY_PIN PIN_VBAT -#define PIN_NFC1 (33) -#define PIN_NFC2 (2) -#define PIN_PIEZO (37) -static const uint8_t AREF = PIN_AREF; - -/* - * Serial interfaces - */ -#define PIN_SERIAL1_RX (1) -#define PIN_SERIAL1_TX (0) - -/* - * SPI Interfaces - */ -#define SPI_INTERFACES_COUNT 1 - -#define PIN_SPI_MISO (24) -#define PIN_SPI_MOSI (25) -#define PIN_SPI_SCK (26) - -static const uint8_t SS = (5); -static const uint8_t MOSI = PIN_SPI_MOSI; -static const uint8_t MISO = PIN_SPI_MISO; -static const uint8_t SCK = PIN_SPI_SCK; - -/* - * Wire Interfaces - */ -#define WIRE_INTERFACES_COUNT 1 - -#define PIN_WIRE_SDA (22) -#define PIN_WIRE_SCL (23) - -// I2C device addresses -#define I2C_ADDR_BQ27441 0x55 // Battery gauge - -// SX1262 declaration -#define USE_SX1262 - -// CUSTOM GPIOs the SX1262 -#define SX126X_CS (32) - -// If you would prefer to get console debug output over the JTAG ICE connection rather than the CDC-ACM USB serial device, just -// define this. #define USE_SEGGER - -#define SX126X_DIO1 (29) -#define SX1262_DIO2 (30) -#define SX126X_BUSY (33) // Supposed to be P0.18 but because of reworks, now on P0.31 (18) -#define SX126X_RESET (34) -// #define SX126X_ANT_SW (32 + 10) -#define SX126X_RXEN (14) -#define SX126X_TXEN (31) -#define SX126X_POWER_EN \ - (15) // FIXME, see warning hre https://github.com/BigCorvus/SX1262-LoRa-BLE-Relay/blob/master/LORA_RELAY_NRF52840.ino -// Indicates this SX1262 is inside of an ebyte E22 module and special config should be done for that -#define SX126X_DIO3_TCXO_VOLTAGE 1.8 - -// ST7565 SPI -#define ST7735_RESET (11) // Output -#define ST7735_CS (12) -#define TFT_BL (13) -#define ST7735_RS (9) -#define ST7735_SDA (39) // actually spi MOSI -#define ST7735_SCK (37) // actually spi clk - -#define PIN_GPS_EN 36 // Just kill GPS power when we want it to sleep? FIXME -#define GPS_EN_ACTIVE 0 // GPS Power output is active low - -// #define LORA_DISABLE_SENDING // The board can brownout during lora TX if you don't have a battery connected. Disable sending -// to allow USB power only based debugging - -#ifdef __cplusplus -} -#endif - -/*---------------------------------------------------------------------------- - * Arduino objects - C++ only - *----------------------------------------------------------------------------*/ - -#endif \ No newline at end of file From 8acc9ccf5fcd95046fea7574dd4cbe57c87bcfa7 Mon Sep 17 00:00:00 2001 From: Tom Fifield Date: Sat, 5 Oct 2024 18:26:54 +0800 Subject: [PATCH 61/88] Remove support for pca10056-rc-clock (#4955) In 2020, geeksville had a NRF52840-dk development board with a busted oscilliator. Let's retire it from service :) Co-authored-by: Ben Meadors --- boards/nrf52840_dk_modified.json | 47 ------- platformio.ini | 1 - variants/pca10056-rc-clock/platformio.ini | 9 -- variants/pca10056-rc-clock/variant.cpp | 42 ------ variants/pca10056-rc-clock/variant.h | 162 ---------------------- 5 files changed, 261 deletions(-) delete mode 100644 boards/nrf52840_dk_modified.json delete mode 100644 variants/pca10056-rc-clock/platformio.ini delete mode 100644 variants/pca10056-rc-clock/variant.cpp delete mode 100644 variants/pca10056-rc-clock/variant.h diff --git a/boards/nrf52840_dk_modified.json b/boards/nrf52840_dk_modified.json deleted file mode 100644 index 2932cb4b9..000000000 --- a/boards/nrf52840_dk_modified.json +++ /dev/null @@ -1,47 +0,0 @@ -{ - "build": { - "arduino": { - "ldscript": "nrf52840_s113_v7.ld" - }, - "core": "nRF5", - "cpu": "cortex-m4", - "extra_flags": "-DARDUINO_NRF52840_PCA10056 -DNRF52840_XXAA", - "f_cpu": "64000000L", - "hwids": [["0x239A", "0x4404"]], - "usb_product": "nrf52840dk", - "mcu": "nrf52840", - "variant": "pca10056-rc-clock", - "variants_dir": "variants", - "bsp": { - "name": "adafruit" - }, - "softdevice": { - "sd_flags": "-DS140", - "sd_name": "s140", - "sd_version": "6.1.1", - "sd_fwid": "0x00B6" - }, - "bootloader": { - "settings_addr": "0xFF000" - } - }, - "connectivity": ["bluetooth"], - "debug": { - "jlink_device": "nRF52840_xxAA", - "onboard_tools": ["jlink"], - "svd_path": "nrf52840.svd", - "openocd_target": "nrf52840-mdk-rs" - }, - "frameworks": ["arduino"], - "name": "A modified NRF52840-DK devboard (Adafruit BSP)", - "upload": { - "maximum_ram_size": 248832, - "maximum_size": 815104, - "require_upload_port": true, - "speed": 115200, - "protocol": "jlink", - "protocols": ["jlink", "nrfjprog", "stlink"] - }, - "url": "https://meshtastic.org/", - "vendor": "Nordic Semi" -} diff --git a/platformio.ini b/platformio.ini index d4cd89631..5dcf61afd 100644 --- a/platformio.ini +++ b/platformio.ini @@ -19,7 +19,6 @@ default_envs = tbeam ;default_envs = tlora-t3s3-v1 ;default_envs = t-echo ;default_envs = canaryone -;default_envs = nrf52840dk-geeksville ;default_envs = native ;default_envs = nano-g1 ;default_envs = pca10059_diy_eink diff --git a/variants/pca10056-rc-clock/platformio.ini b/variants/pca10056-rc-clock/platformio.ini deleted file mode 100644 index f8cff4d73..000000000 --- a/variants/pca10056-rc-clock/platformio.ini +++ /dev/null @@ -1,9 +0,0 @@ -; The NRF52840-dk development board, but @geeksville's board - which has a busted oscilliator -[env:nrf52840dk-geeksville] -board_level = extra -extends = nrf52840_base -board = nrf52840_dk_modified -# add our variants files to the include and src paths -build_flags = ${nrf52_base.build_flags} -Ivariants/pca10056-rc-clock - -L "${platformio.libdeps_dir}/${this.__env__}/bsec2/src/cortex-m4/fpv4-sp-d16-hard" -build_src_filter = ${nrf52_base.build_src_filter} +<../variants/pca10056-rc-clock> \ No newline at end of file diff --git a/variants/pca10056-rc-clock/variant.cpp b/variants/pca10056-rc-clock/variant.cpp deleted file mode 100644 index a1882a33f..000000000 --- a/variants/pca10056-rc-clock/variant.cpp +++ /dev/null @@ -1,42 +0,0 @@ -/* - Copyright (c) 2014-2015 Arduino LLC. All right reserved. - Copyright (c) 2016 Sandeep Mistry All right reserved. - Copyright (c) 2018, Adafruit Industries (adafruit.com) - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - See the GNU Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#include "variant.h" -#include "nrf.h" -#include "wiring_constants.h" -#include "wiring_digital.h" - -const uint32_t g_ADigitalPinMap[] = { - // P0 - 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, - - // P1 - 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47}; - -void initVariant() -{ - // LED1 & LED2 - pinMode(PIN_LED1, OUTPUT); - ledOff(PIN_LED1); - - pinMode(PIN_LED2, OUTPUT); - ledOff(PIN_LED2); - ; -} diff --git a/variants/pca10056-rc-clock/variant.h b/variants/pca10056-rc-clock/variant.h deleted file mode 100644 index 032e1de2b..000000000 --- a/variants/pca10056-rc-clock/variant.h +++ /dev/null @@ -1,162 +0,0 @@ -/* - Copyright (c) 2014-2015 Arduino LLC. All right reserved. - Copyright (c) 2016 Sandeep Mistry All right reserved. - Copyright (c) 2018, Adafruit Industries (adafruit.com) - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - See the GNU Lesser General Public License for more details. - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#ifndef _VARIANT_PCA10056_ -#define _VARIANT_PCA10056_ - -/** Master clock frequency */ -#define VARIANT_MCK (64000000ul) - -// This file is the same as the standard pac10056 variant, except that @geeksville broke the xtal on his devboard so -// he has to use a RC clock. - -// #define USE_LFXO // Board uses 32khz crystal for LF -#define USE_LFRC // Board uses RC for LF - -/*---------------------------------------------------------------------------- - * Headers - *----------------------------------------------------------------------------*/ - -#include "WVariant.h" - -#ifdef __cplusplus -extern "C" { -#endif // __cplusplus - -// Number of pins defined in PinDescription array -#define PINS_COUNT (48) -#define NUM_DIGITAL_PINS (48) -#define NUM_ANALOG_INPUTS (6) -#define NUM_ANALOG_OUTPUTS (0) - -// LEDs -#define PIN_LED1 (13) -#define PIN_LED2 (14) - -#define LED_BUILTIN PIN_LED1 -#define LED_CONN PIN_LED2 - -#define LED_RED PIN_LED1 -#define LED_BLUE PIN_LED2 - -#define LED_STATE_ON 0 // State when LED is litted - -/* - * Buttons - */ -#define PIN_BUTTON1 11 -#define PIN_BUTTON2 12 -#define PIN_BUTTON3 24 -#define PIN_BUTTON4 25 - -/* - * Analog pins - */ -#define PIN_A0 (3) -#define PIN_A1 (4) -#define PIN_A2 (28) -#define PIN_A3 (29) -#define PIN_A4 (30) -#define PIN_A5 (31) -#define PIN_A6 (0xff) -#define PIN_A7 (0xff) - -static const uint8_t A0 = PIN_A0; -static const uint8_t A1 = PIN_A1; -static const uint8_t A2 = PIN_A2; -static const uint8_t A3 = PIN_A3; -static const uint8_t A4 = PIN_A4; -static const uint8_t A5 = PIN_A5; -static const uint8_t A6 = PIN_A6; -static const uint8_t A7 = PIN_A7; -#define ADC_RESOLUTION 14 - -// Other pins -#define PIN_AREF (2) -#define PIN_NFC1 (9) -#define PIN_NFC2 (10) - -static const uint8_t AREF = PIN_AREF; - -/* - * Serial interfaces - */ - -// Arduino Header D0, D1 -#define PIN_SERIAL1_RX (33) // P1.01 -#define PIN_SERIAL1_TX (34) // P1.02 - -// Connected to Jlink CDC -#define PIN_SERIAL2_RX (8) -#define PIN_SERIAL2_TX (6) - -/* - * SPI Interfaces - */ -#define SPI_INTERFACES_COUNT 1 - -#define PIN_SPI_MISO (46) -#define PIN_SPI_MOSI (45) -#define PIN_SPI_SCK (47) - -static const uint8_t SS = 44; -static const uint8_t MOSI = PIN_SPI_MOSI; -static const uint8_t MISO = PIN_SPI_MISO; -static const uint8_t SCK = PIN_SPI_SCK; - -/* - * Wire Interfaces - */ -#define WIRE_INTERFACES_COUNT 1 - -#define PIN_WIRE_SDA (26) -#define PIN_WIRE_SCL (27) - -// QSPI Pins -#define PIN_QSPI_SCK 19 -#define PIN_QSPI_CS 17 -#define PIN_QSPI_IO0 20 -#define PIN_QSPI_IO1 21 -#define PIN_QSPI_IO2 22 -#define PIN_QSPI_IO3 23 - -// On-board QSPI Flash -#define EXTERNAL_FLASH_DEVICES MX25R6435F -#define EXTERNAL_FLASH_USE_QSPI - -// CUSTOM GPIOs the SX1262MB2CAS shield when installed on the NRF52840-DK development board -#define USE_SX1262 -#define SX126X_CS (32 + 8) // P1.08 -#define SX126X_DIO1 (32 + 6) // P1.06 -#define SX126X_BUSY (32 + 4) // P1.04 -#define SX126X_RESET (0 + 3) // P0.03 -#define SX126X_ANT_SW (32 + 10) // P1.10 -#define SX126X_DIO2_AS_RF_SWITCH - -// To debug via the segger JLINK console rather than the CDC-ACM serial device -// #define USE_SEGGER - -#ifdef __cplusplus -} -#endif - -/*---------------------------------------------------------------------------- - * Arduino objects - C++ only - *----------------------------------------------------------------------------*/ - -#endif From dac433ed2feb9eabcffd7297dc5f32c30db8c60f Mon Sep 17 00:00:00 2001 From: Tom Fifield Date: Sat, 5 Oct 2024 18:27:15 +0800 Subject: [PATCH 62/88] Remove rak4631_epaper_onrxtx variant (#4958) Appears to be a testing variant of rak4631_epaper. Due to little information available, let's remove it for now. --- variants/rak4631_epaper_onrxtx/platformio.ini | 25 --- variants/rak4631_epaper_onrxtx/variant.cpp | 45 ---- variants/rak4631_epaper_onrxtx/variant.h | 205 ------------------ 3 files changed, 275 deletions(-) delete mode 100644 variants/rak4631_epaper_onrxtx/platformio.ini delete mode 100644 variants/rak4631_epaper_onrxtx/variant.cpp delete mode 100644 variants/rak4631_epaper_onrxtx/variant.h diff --git a/variants/rak4631_epaper_onrxtx/platformio.ini b/variants/rak4631_epaper_onrxtx/platformio.ini deleted file mode 100644 index 8c1b8eee8..000000000 --- a/variants/rak4631_epaper_onrxtx/platformio.ini +++ /dev/null @@ -1,25 +0,0 @@ -; The very slick RAK wireless RAK 4631 / 4630 board - Firmware for 5005 with the RAK 14000 ePaper -[env:rak4631_eink_onrxtx] -board_level = extra -extends = nrf52840_base -board = wiscore_rak4631 -build_flags = ${nrf52840_base.build_flags} -Ivariants/rak4631_epaper -D RAK_4631 - -L "${platformio.libdeps_dir}/${this.__env__}/bsec2/src/cortex-m4/fpv4-sp-d16-hard" - -D PIN_EINK_EN=34 - -D EINK_DISPLAY_MODEL=GxEPD2_213_BN - -D EINK_WIDTH=250 - -D EINK_HEIGHT=122 - -D RADIOLIB_EXCLUDE_SX128X=1 - -D RADIOLIB_EXCLUDE_SX127X=1 - -D RADIOLIB_EXCLUDE_LR11X0=1 -build_src_filter = ${nrf52_base.build_src_filter} +<../variants/rak4631_epaper_onrxtx> -lib_deps = - ${nrf52840_base.lib_deps} - zinggjm/GxEPD2@^1.5.1 - melopero/Melopero RV3028@^1.1.0 - rakwireless/RAKwireless NCP5623 RGB LED library@^1.0.2 - beegee-tokyo/RAKwireless RAK12034@^1.0.0 -debug_tool = jlink -; If not set we will default to uploading over serial (first it forces bootloader entry by talking 1200bps to cdcacm) -;upload_protocol = jlink -;upload_port = /dev/ttyACM3 \ No newline at end of file diff --git a/variants/rak4631_epaper_onrxtx/variant.cpp b/variants/rak4631_epaper_onrxtx/variant.cpp deleted file mode 100644 index e84b60b3b..000000000 --- a/variants/rak4631_epaper_onrxtx/variant.cpp +++ /dev/null @@ -1,45 +0,0 @@ -/* - Copyright (c) 2014-2015 Arduino LLC. All right reserved. - Copyright (c) 2016 Sandeep Mistry All right reserved. - Copyright (c) 2018, Adafruit Industries (adafruit.com) - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - See the GNU Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#include "variant.h" -#include "nrf.h" -#include "wiring_constants.h" -#include "wiring_digital.h" - -const uint32_t g_ADigitalPinMap[] = { - // P0 - 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, - - // P1 - 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47}; - -void initVariant() -{ - // LED1 & LED2 - pinMode(PIN_LED1, OUTPUT); - ledOff(PIN_LED1); - - pinMode(PIN_LED2, OUTPUT); - ledOff(PIN_LED2); - - // 3V3 Power Rail - pinMode(PIN_3V3_EN, OUTPUT); - digitalWrite(PIN_3V3_EN, HIGH); -} diff --git a/variants/rak4631_epaper_onrxtx/variant.h b/variants/rak4631_epaper_onrxtx/variant.h deleted file mode 100644 index 5888cff33..000000000 --- a/variants/rak4631_epaper_onrxtx/variant.h +++ /dev/null @@ -1,205 +0,0 @@ -#ifndef _VARIANT_RAK4630_ -#define _VARIANT_RAK4630_ - -#define RAK4630 - -/** Master clock frequency */ -#define VARIANT_MCK (64000000ul) - -#define USE_LFXO // Board uses 32khz crystal for LF -// define USE_LFRC // Board uses RC for LF - -/*---------------------------------------------------------------------------- - * Headers - *----------------------------------------------------------------------------*/ - -#include "WVariant.h" - -#ifdef __cplusplus -extern "C" { -#endif // __cplusplus - -// Number of pins defined in PinDescription array -#define PINS_COUNT (48) -#define NUM_DIGITAL_PINS (48) -#define NUM_ANALOG_INPUTS (6) -#define NUM_ANALOG_OUTPUTS (0) - -// LEDs -#define PIN_LED1 (35) -#define PIN_LED2 (36) - -#define LED_BUILTIN PIN_LED1 -#define LED_CONN PIN_LED2 - -#define LED_GREEN PIN_LED1 -#define LED_BLUE PIN_LED2 - -#define LED_STATE_ON 1 // State when LED is litted - -/* - * Buttons - */ - -#define PIN_BUTTON1 9 // Pin for button on E-ink button module or IO expansion -#define BUTTON_NEED_PULLUP -// #define PIN_BUTTON2 12 - -/* - * Analog pins - */ -#define PIN_A0 (-1) //(5) -#define PIN_A1 (31) -#define PIN_A2 (28) -#define PIN_A3 (29) -#define PIN_A4 (30) -#define PIN_A5 (31) -#define PIN_A6 (0xff) -#define PIN_A7 (0xff) - -static const uint8_t A0 = PIN_A0; -static const uint8_t A1 = PIN_A1; -static const uint8_t A2 = PIN_A2; -static const uint8_t A3 = PIN_A3; -static const uint8_t A4 = PIN_A4; -static const uint8_t A5 = PIN_A5; -static const uint8_t A6 = PIN_A6; -static const uint8_t A7 = PIN_A7; -#define ADC_RESOLUTION 14 - -// Other pins -#define PIN_AREF (2) -// #define PIN_NFC1 (9) -// #define PIN_NFC2 (10) - -static const uint8_t AREF = PIN_AREF; - -/* - * Serial interfaces - */ -#define PIN_SERIAL1_RX (-1) -#define PIN_SERIAL1_TX (-1) - -// Connected to Jlink CDC -#define PIN_SERIAL2_RX (-1) -#define PIN_SERIAL2_TX (-1) - -// Testing USB detection -#define NRF_APM - -/* - * SPI Interfaces - */ -#define SPI_INTERFACES_COUNT 2 - -#define PIN_SPI_MISO (45) -#define PIN_SPI_MOSI (44) -#define PIN_SPI_SCK (43) - -#define PIN_SPI1_MISO (-1) -#define PIN_SPI1_MOSI (0 + 13) -#define PIN_SPI1_SCK (0 + 14) - -static const uint8_t SS = 42; -static const uint8_t MOSI = PIN_SPI_MOSI; -static const uint8_t MISO = PIN_SPI_MISO; -static const uint8_t SCK = PIN_SPI_SCK; - -/* - * eink display pins - */ - -#define USE_EINK - -#define PIN_EINK_CS (0 + 16) // TX1 -#define PIN_EINK_BUSY (0 + 15) // RX1 -#define PIN_EINK_DC (0 + 17) // IO1 -// #define PIN_EINK_RES (-1) //first try without RESET then connect it to AIN (AIN0 5 ) -#define PIN_EINK_RES (0 + 5) // 2.13 BN Display needs RESET -#define PIN_EINK_SCLK (0 + 14) // SCL -#define PIN_EINK_MOSI (0 + 13) // SDA - -// RAKRGB -#define HAS_NCP5623 - -/* - * Wire Interfaces - */ -#define WIRE_INTERFACES_COUNT 1 - -#define PIN_WIRE_SDA (13) -#define PIN_WIRE_SCL (14) - -/* @note RAK5005-O GPIO mapping to RAK4631 GPIO ports - RAK5005-O <-> nRF52840 - IO1 <-> P0.17 (Arduino GPIO number 17) - IO2 <-> P1.02 (Arduino GPIO number 34) - IO3 <-> P0.21 (Arduino GPIO number 21) - IO4 <-> P0.04 (Arduino GPIO number 4) - IO5 <-> P0.09 (Arduino GPIO number 9) - IO6 <-> P0.10 (Arduino GPIO number 10) - IO7 <-> P0.28 (Arduino GPIO number 28) - SW1 <-> P0.01 (Arduino GPIO number 1) - A0 <-> P0.04/AIN2 (Arduino Analog A2 - A1 <-> P0.31/AIN7 (Arduino Analog A7 - SPI_CS <-> P0.26 (Arduino GPIO number 26) - */ - -// RAK4630 LoRa module -#define USE_SX1262 -#define SX126X_CS (42) -#define SX126X_DIO1 (47) -#define SX126X_BUSY (46) -#define SX126X_RESET (38) -// #define SX126X_TXEN (39) -// #define SX126X_RXEN (37) -#define SX126X_POWER_EN (37) -// DIO2 controlls an antenna switch and the TCXO voltage is controlled by DIO3 -#define SX126X_DIO2_AS_RF_SWITCH -#define SX126X_DIO3_TCXO_VOLTAGE 1.8 - -// enables 3.3V periphery like GPS or IO Module -#define PIN_3V3_EN (34) - -// NO GPS -#undef GPS_RX_PIN -#undef GPS_TX_PIN - -// RAK1910 GPS module -// If using the wisblock GPS module and pluged into Port A on WisBlock base -// IO1 is hooked to PPS (pin 12 on header) = gpio 17 -// IO2 is hooked to GPS RESET = gpio 34, but it can not be used to this because IO2 is ALSO used to control 3V3_S power (1 is on). -// Therefore must be 1 to keep peripherals powered -// Power is on the controllable 3V3_S rail -// #define PIN_GPS_RESET (34) -// #define PIN_GPS_EN PIN_3V3_EN -// #define PIN_GPS_PPS (17) // Pulse per second input from the GPS - -// #define GPS_RX_PIN PIN_SERIAL1_RX -// #define GPS_TX_PIN PIN_SERIAL1_TX - -// RAK12002 RTC Module -#define RV3028_RTC (uint8_t)0b1010010 - -// Battery -// The battery sense is hooked to pin A0 (5) -// #define BATTERY_PIN PIN_A0 -// and has 12 bit resolution -// #define BATTERY_SENSE_RESOLUTION_BITS 12 -// #define BATTERY_SENSE_RESOLUTION 4096.0 -// #undef AREF_VOLTAGE -// #define AREF_VOLTAGE 3.0 -// #define VBAT_AR_INTERNAL AR_INTERNAL_3_0 -// #define ADC_MULTIPLIER 1.73 - -// #define HAS_RTC 1 - -#ifdef __cplusplus -} -#endif - -/*---------------------------------------------------------------------------- - * Arduino objects - C++ only - *----------------------------------------------------------------------------*/ - -#endif \ No newline at end of file From 0c90a2274f95c5a434454a856de519dcb562454b Mon Sep 17 00:00:00 2001 From: Tom Fifield Date: Sat, 5 Oct 2024 18:39:13 +0800 Subject: [PATCH 63/88] Remove unused headers (#4954) These files had existing since 2020 without being used/modified. --- src/platform/esp32/CallbackCharacteristic.h | 12 ------------ src/platform/nrf52/pgmspace.h | 5 ----- 2 files changed, 17 deletions(-) delete mode 100644 src/platform/esp32/CallbackCharacteristic.h delete mode 100644 src/platform/nrf52/pgmspace.h diff --git a/src/platform/esp32/CallbackCharacteristic.h b/src/platform/esp32/CallbackCharacteristic.h deleted file mode 100644 index cd3bc6f51..000000000 --- a/src/platform/esp32/CallbackCharacteristic.h +++ /dev/null @@ -1,12 +0,0 @@ -#pragma once -#include "BLECharacteristic.h" -#include "PowerFSM.h" // FIXME - someday I want to make this OTA thing a separate lb at at that point it can't touch this - -/** - * A characteristic with a set of overridable callbacks - */ -class CallbackCharacteristic : public BLECharacteristic, public BLECharacteristicCallbacks -{ - public: - CallbackCharacteristic(const char *uuid, uint32_t btprops) : BLECharacteristic(uuid, btprops) { setCallbacks(this); } -}; diff --git a/src/platform/nrf52/pgmspace.h b/src/platform/nrf52/pgmspace.h deleted file mode 100644 index 5ad8035be..000000000 --- a/src/platform/nrf52/pgmspace.h +++ /dev/null @@ -1,5 +0,0 @@ -#pragma once - -// dummy file to keep old arduino code happy -#define PROGMEM -#define pgm_read_byte(addr) (*((unsigned const char *)addr)) \ No newline at end of file From d650001caac2a1fb68c738e20613375af9eef349 Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Sat, 5 Oct 2024 08:05:44 -0500 Subject: [PATCH 64/88] [create-pull-request] automated change (#4960) Co-authored-by: thebentern <9000580+thebentern@users.noreply.github.com> --- version.properties | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/version.properties b/version.properties index f6a385c9f..df7ba70c7 100644 --- a/version.properties +++ b/version.properties @@ -1,4 +1,4 @@ [VERSION] major = 2 minor = 5 -build = 5 +build = 6 From a6f96cb9b4b2bc95e406d0d527e88d37d761fbae Mon Sep 17 00:00:00 2001 From: Tom Fifield Date: Sat, 5 Oct 2024 22:27:10 +0800 Subject: [PATCH 65/88] Revert "Remove rak4631_epaper_onrxtx variant (#4958)" (#4963) This reverts commit dac433ed2feb9eabcffd7297dc5f32c30db8c60f. --- variants/rak4631_epaper_onrxtx/platformio.ini | 25 +++ variants/rak4631_epaper_onrxtx/variant.cpp | 45 ++++ variants/rak4631_epaper_onrxtx/variant.h | 205 ++++++++++++++++++ 3 files changed, 275 insertions(+) create mode 100644 variants/rak4631_epaper_onrxtx/platformio.ini create mode 100644 variants/rak4631_epaper_onrxtx/variant.cpp create mode 100644 variants/rak4631_epaper_onrxtx/variant.h diff --git a/variants/rak4631_epaper_onrxtx/platformio.ini b/variants/rak4631_epaper_onrxtx/platformio.ini new file mode 100644 index 000000000..8c1b8eee8 --- /dev/null +++ b/variants/rak4631_epaper_onrxtx/platformio.ini @@ -0,0 +1,25 @@ +; The very slick RAK wireless RAK 4631 / 4630 board - Firmware for 5005 with the RAK 14000 ePaper +[env:rak4631_eink_onrxtx] +board_level = extra +extends = nrf52840_base +board = wiscore_rak4631 +build_flags = ${nrf52840_base.build_flags} -Ivariants/rak4631_epaper -D RAK_4631 + -L "${platformio.libdeps_dir}/${this.__env__}/bsec2/src/cortex-m4/fpv4-sp-d16-hard" + -D PIN_EINK_EN=34 + -D EINK_DISPLAY_MODEL=GxEPD2_213_BN + -D EINK_WIDTH=250 + -D EINK_HEIGHT=122 + -D RADIOLIB_EXCLUDE_SX128X=1 + -D RADIOLIB_EXCLUDE_SX127X=1 + -D RADIOLIB_EXCLUDE_LR11X0=1 +build_src_filter = ${nrf52_base.build_src_filter} +<../variants/rak4631_epaper_onrxtx> +lib_deps = + ${nrf52840_base.lib_deps} + zinggjm/GxEPD2@^1.5.1 + melopero/Melopero RV3028@^1.1.0 + rakwireless/RAKwireless NCP5623 RGB LED library@^1.0.2 + beegee-tokyo/RAKwireless RAK12034@^1.0.0 +debug_tool = jlink +; If not set we will default to uploading over serial (first it forces bootloader entry by talking 1200bps to cdcacm) +;upload_protocol = jlink +;upload_port = /dev/ttyACM3 \ No newline at end of file diff --git a/variants/rak4631_epaper_onrxtx/variant.cpp b/variants/rak4631_epaper_onrxtx/variant.cpp new file mode 100644 index 000000000..e84b60b3b --- /dev/null +++ b/variants/rak4631_epaper_onrxtx/variant.cpp @@ -0,0 +1,45 @@ +/* + Copyright (c) 2014-2015 Arduino LLC. All right reserved. + Copyright (c) 2016 Sandeep Mistry All right reserved. + Copyright (c) 2018, Adafruit Industries (adafruit.com) + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + See the GNU Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include "variant.h" +#include "nrf.h" +#include "wiring_constants.h" +#include "wiring_digital.h" + +const uint32_t g_ADigitalPinMap[] = { + // P0 + 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, + + // P1 + 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47}; + +void initVariant() +{ + // LED1 & LED2 + pinMode(PIN_LED1, OUTPUT); + ledOff(PIN_LED1); + + pinMode(PIN_LED2, OUTPUT); + ledOff(PIN_LED2); + + // 3V3 Power Rail + pinMode(PIN_3V3_EN, OUTPUT); + digitalWrite(PIN_3V3_EN, HIGH); +} diff --git a/variants/rak4631_epaper_onrxtx/variant.h b/variants/rak4631_epaper_onrxtx/variant.h new file mode 100644 index 000000000..5888cff33 --- /dev/null +++ b/variants/rak4631_epaper_onrxtx/variant.h @@ -0,0 +1,205 @@ +#ifndef _VARIANT_RAK4630_ +#define _VARIANT_RAK4630_ + +#define RAK4630 + +/** Master clock frequency */ +#define VARIANT_MCK (64000000ul) + +#define USE_LFXO // Board uses 32khz crystal for LF +// define USE_LFRC // Board uses RC for LF + +/*---------------------------------------------------------------------------- + * Headers + *----------------------------------------------------------------------------*/ + +#include "WVariant.h" + +#ifdef __cplusplus +extern "C" { +#endif // __cplusplus + +// Number of pins defined in PinDescription array +#define PINS_COUNT (48) +#define NUM_DIGITAL_PINS (48) +#define NUM_ANALOG_INPUTS (6) +#define NUM_ANALOG_OUTPUTS (0) + +// LEDs +#define PIN_LED1 (35) +#define PIN_LED2 (36) + +#define LED_BUILTIN PIN_LED1 +#define LED_CONN PIN_LED2 + +#define LED_GREEN PIN_LED1 +#define LED_BLUE PIN_LED2 + +#define LED_STATE_ON 1 // State when LED is litted + +/* + * Buttons + */ + +#define PIN_BUTTON1 9 // Pin for button on E-ink button module or IO expansion +#define BUTTON_NEED_PULLUP +// #define PIN_BUTTON2 12 + +/* + * Analog pins + */ +#define PIN_A0 (-1) //(5) +#define PIN_A1 (31) +#define PIN_A2 (28) +#define PIN_A3 (29) +#define PIN_A4 (30) +#define PIN_A5 (31) +#define PIN_A6 (0xff) +#define PIN_A7 (0xff) + +static const uint8_t A0 = PIN_A0; +static const uint8_t A1 = PIN_A1; +static const uint8_t A2 = PIN_A2; +static const uint8_t A3 = PIN_A3; +static const uint8_t A4 = PIN_A4; +static const uint8_t A5 = PIN_A5; +static const uint8_t A6 = PIN_A6; +static const uint8_t A7 = PIN_A7; +#define ADC_RESOLUTION 14 + +// Other pins +#define PIN_AREF (2) +// #define PIN_NFC1 (9) +// #define PIN_NFC2 (10) + +static const uint8_t AREF = PIN_AREF; + +/* + * Serial interfaces + */ +#define PIN_SERIAL1_RX (-1) +#define PIN_SERIAL1_TX (-1) + +// Connected to Jlink CDC +#define PIN_SERIAL2_RX (-1) +#define PIN_SERIAL2_TX (-1) + +// Testing USB detection +#define NRF_APM + +/* + * SPI Interfaces + */ +#define SPI_INTERFACES_COUNT 2 + +#define PIN_SPI_MISO (45) +#define PIN_SPI_MOSI (44) +#define PIN_SPI_SCK (43) + +#define PIN_SPI1_MISO (-1) +#define PIN_SPI1_MOSI (0 + 13) +#define PIN_SPI1_SCK (0 + 14) + +static const uint8_t SS = 42; +static const uint8_t MOSI = PIN_SPI_MOSI; +static const uint8_t MISO = PIN_SPI_MISO; +static const uint8_t SCK = PIN_SPI_SCK; + +/* + * eink display pins + */ + +#define USE_EINK + +#define PIN_EINK_CS (0 + 16) // TX1 +#define PIN_EINK_BUSY (0 + 15) // RX1 +#define PIN_EINK_DC (0 + 17) // IO1 +// #define PIN_EINK_RES (-1) //first try without RESET then connect it to AIN (AIN0 5 ) +#define PIN_EINK_RES (0 + 5) // 2.13 BN Display needs RESET +#define PIN_EINK_SCLK (0 + 14) // SCL +#define PIN_EINK_MOSI (0 + 13) // SDA + +// RAKRGB +#define HAS_NCP5623 + +/* + * Wire Interfaces + */ +#define WIRE_INTERFACES_COUNT 1 + +#define PIN_WIRE_SDA (13) +#define PIN_WIRE_SCL (14) + +/* @note RAK5005-O GPIO mapping to RAK4631 GPIO ports + RAK5005-O <-> nRF52840 + IO1 <-> P0.17 (Arduino GPIO number 17) + IO2 <-> P1.02 (Arduino GPIO number 34) + IO3 <-> P0.21 (Arduino GPIO number 21) + IO4 <-> P0.04 (Arduino GPIO number 4) + IO5 <-> P0.09 (Arduino GPIO number 9) + IO6 <-> P0.10 (Arduino GPIO number 10) + IO7 <-> P0.28 (Arduino GPIO number 28) + SW1 <-> P0.01 (Arduino GPIO number 1) + A0 <-> P0.04/AIN2 (Arduino Analog A2 + A1 <-> P0.31/AIN7 (Arduino Analog A7 + SPI_CS <-> P0.26 (Arduino GPIO number 26) + */ + +// RAK4630 LoRa module +#define USE_SX1262 +#define SX126X_CS (42) +#define SX126X_DIO1 (47) +#define SX126X_BUSY (46) +#define SX126X_RESET (38) +// #define SX126X_TXEN (39) +// #define SX126X_RXEN (37) +#define SX126X_POWER_EN (37) +// DIO2 controlls an antenna switch and the TCXO voltage is controlled by DIO3 +#define SX126X_DIO2_AS_RF_SWITCH +#define SX126X_DIO3_TCXO_VOLTAGE 1.8 + +// enables 3.3V periphery like GPS or IO Module +#define PIN_3V3_EN (34) + +// NO GPS +#undef GPS_RX_PIN +#undef GPS_TX_PIN + +// RAK1910 GPS module +// If using the wisblock GPS module and pluged into Port A on WisBlock base +// IO1 is hooked to PPS (pin 12 on header) = gpio 17 +// IO2 is hooked to GPS RESET = gpio 34, but it can not be used to this because IO2 is ALSO used to control 3V3_S power (1 is on). +// Therefore must be 1 to keep peripherals powered +// Power is on the controllable 3V3_S rail +// #define PIN_GPS_RESET (34) +// #define PIN_GPS_EN PIN_3V3_EN +// #define PIN_GPS_PPS (17) // Pulse per second input from the GPS + +// #define GPS_RX_PIN PIN_SERIAL1_RX +// #define GPS_TX_PIN PIN_SERIAL1_TX + +// RAK12002 RTC Module +#define RV3028_RTC (uint8_t)0b1010010 + +// Battery +// The battery sense is hooked to pin A0 (5) +// #define BATTERY_PIN PIN_A0 +// and has 12 bit resolution +// #define BATTERY_SENSE_RESOLUTION_BITS 12 +// #define BATTERY_SENSE_RESOLUTION 4096.0 +// #undef AREF_VOLTAGE +// #define AREF_VOLTAGE 3.0 +// #define VBAT_AR_INTERNAL AR_INTERNAL_3_0 +// #define ADC_MULTIPLIER 1.73 + +// #define HAS_RTC 1 + +#ifdef __cplusplus +} +#endif + +/*---------------------------------------------------------------------------- + * Arduino objects - C++ only + *----------------------------------------------------------------------------*/ + +#endif \ No newline at end of file From 8a370c538149f5af659573963cd2f59fa669661e Mon Sep 17 00:00:00 2001 From: Tom Fifield Date: Sun, 6 Oct 2024 08:34:51 +0800 Subject: [PATCH 66/88] Revert "Revert "Remove unused Jlink monitoring files (#4953)" (#4959)" (#4966) This reverts commit 783466f1165aeddd41ab1b1b76ef70aa2908c3b1. --- src/platform/nrf52/JLINK_MONITOR.c | 124 --- src/platform/nrf52/JLINK_MONITOR.h | 27 - src/platform/nrf52/JLINK_MONITOR_ISR_SES.S | 888 --------------------- 3 files changed, 1039 deletions(-) delete mode 100644 src/platform/nrf52/JLINK_MONITOR.c delete mode 100644 src/platform/nrf52/JLINK_MONITOR.h delete mode 100644 src/platform/nrf52/JLINK_MONITOR_ISR_SES.S diff --git a/src/platform/nrf52/JLINK_MONITOR.c b/src/platform/nrf52/JLINK_MONITOR.c deleted file mode 100644 index 160264905..000000000 --- a/src/platform/nrf52/JLINK_MONITOR.c +++ /dev/null @@ -1,124 +0,0 @@ -/********************************************************************* -* SEGGER Microcontroller GmbH & Co. KG * -* The Embedded Experts * -********************************************************************** -* * -* (c) 1995 - 2015 SEGGER Microcontroller GmbH & Co. KG * -* * -* www.segger.com Support: support@segger.com * -* * -********************************************************************** - ----------------------------------------------------------------------- -File : JLINK_MONITOR.c -Purpose : Implementation of debug monitor for J-Link monitor mode debug on Cortex-M devices. --------- END-OF-HEADER --------------------------------------------- -*/ - -#include "JLINK_MONITOR.h" - -/********************************************************************* - * - * Configuration - * - ********************************************************************** - */ - -/********************************************************************* - * - * Defines - * - ********************************************************************** - */ - -/********************************************************************* - * - * Types - * - ********************************************************************** - */ - -/********************************************************************* - * - * Static data - * - ********************************************************************** - */ - -volatile int MAIN_MonCnt; // Incremented in JLINK_MONITOR_OnPoll() while CPU is in debug mode - -/********************************************************************* - * - * Local functions - * - ********************************************************************** - */ - -/********************************************************************* - * - * Global functions - * - ********************************************************************** - */ - -/********************************************************************* - * - * JLINK_MONITOR_OnExit() - * - * Function description - * Called from DebugMon_Handler(), once per debug exit. - * May perform some target specific operations to be done on debug mode exit. - * - * Notes - * (1) Must not keep the CPU busy for more than 100 ms - */ -void JLINK_MONITOR_OnExit(void) -{ - // - // Add custom code here - // - // BSP_ClrLED(0); -} - -/********************************************************************* - * - * JLINK_MONITOR_OnEnter() - * - * Function description - * Called from DebugMon_Handler(), once per debug entry. - * May perform some target specific operations to be done on debug mode entry - * - * Notes - * (1) Must not keep the CPU busy for more than 100 ms - */ -void JLINK_MONITOR_OnEnter(void) -{ - // - // Add custom code here - // - // BSP_SetLED(0); - // BSP_ClrLED(1); -} - -/********************************************************************* - * - * JLINK_MONITOR_OnPoll() - * - * Function description - * Called periodically from DebugMon_Handler(), to perform some actions that need to be performed periodically during debug - * mode. - * - * Notes - * (1) Must not keep the CPU busy for more than 100 ms - */ -void JLINK_MONITOR_OnPoll(void) -{ - // - // Add custom code here - // - MAIN_MonCnt++; - // BSP_ToggleLED(0); - // _Delay(500000); -} - -/****** End Of File *************************************************/ diff --git a/src/platform/nrf52/JLINK_MONITOR.h b/src/platform/nrf52/JLINK_MONITOR.h deleted file mode 100644 index 87cf332fe..000000000 --- a/src/platform/nrf52/JLINK_MONITOR.h +++ /dev/null @@ -1,27 +0,0 @@ -/********************************************************************* -* SEGGER Microcontroller GmbH & Co. KG * -* The Embedded Experts * -********************************************************************** -* * -* (c) 1995 - 2015 SEGGER Microcontroller GmbH & Co. KG * -* * -* www.segger.com Support: support@segger.com * -* * -********************************************************************** - ----------------------------------------------------------------------- -File : JLINK_MONITOR.h -Purpose : Header file of debug monitor for J-Link monitor mode debug on Cortex-M devices. --------- END-OF-HEADER --------------------------------------------- -*/ - -#ifndef JLINK_MONITOR_H -#define JLINK_MONITOR_H - -void JLINK_MONITOR_OnExit(void); -void JLINK_MONITOR_OnEnter(void); -void JLINK_MONITOR_OnPoll(void); - -#endif - -/****** End Of File *************************************************/ diff --git a/src/platform/nrf52/JLINK_MONITOR_ISR_SES.S b/src/platform/nrf52/JLINK_MONITOR_ISR_SES.S deleted file mode 100644 index cda4b1a50..000000000 --- a/src/platform/nrf52/JLINK_MONITOR_ISR_SES.S +++ /dev/null @@ -1,888 +0,0 @@ -/********************************************************************* -* SEGGER Microcontroller GmbH & Co. KG * -* The Embedded Experts * -********************************************************************** -* * -* (c) 1995 - 2015 SEGGER Microcontroller GmbH & Co. KG * -* * -* www.segger.com Support: support@segger.com * -* * -********************************************************************** - ----------------------------------------------------------------------- -File : JLINK_MONITOR_ISR_SES.s -Purpose : Implementation of debug monitor for J-Link monitor mode - debug on Cortex-M devices, supporting SES compiler. --------- END-OF-HEADER --------------------------------------------- -*/ - - .name JLINK_MONITOR_ISR - .syntax unified - - .extern JLINK_MONITOR_OnEnter - .extern JLINK_MONITOR_OnExit - .extern JLINK_MONITOR_OnPoll - - .global DebugMon_Handler - -/********************************************************************* -* -* Defines, configurable -* -********************************************************************** -*/ - -#define _MON_VERSION 100 // V x.yy - -/********************************************************************* -* -* Defines, fixed -* -********************************************************************** -*/ - -#define _APP_SP_OFF_R0 0x00 -#define _APP_SP_OFF_R1 0x04 -#define _APP_SP_OFF_R2 0x08 -#define _APP_SP_OFF_R3 0x0C -#define _APP_SP_OFF_R12 0x10 -#define _APP_SP_OFF_R14_LR 0x14 -#define _APP_SP_OFF_PC 0x18 -#define _APP_SP_OFF_XPSR 0x1C -#define _APP_SP_OFF_S0 0x20 -#define _APP_SP_OFF_S1 0x24 -#define _APP_SP_OFF_S2 0x28 -#define _APP_SP_OFF_S3 0x2C -#define _APP_SP_OFF_S4 0x30 -#define _APP_SP_OFF_S5 0x34 -#define _APP_SP_OFF_S6 0x38 -#define _APP_SP_OFF_S7 0x3C -#define _APP_SP_OFF_S8 0x40 -#define _APP_SP_OFF_S9 0x44 -#define _APP_SP_OFF_S10 0x48 -#define _APP_SP_OFF_S11 0x4C -#define _APP_SP_OFF_S12 0x50 -#define _APP_SP_OFF_S13 0x54 -#define _APP_SP_OFF_S14 0x58 -#define _APP_SP_OFF_S15 0x5C -#define _APP_SP_OFF_FPSCR 0x60 - -#define _NUM_BYTES_BASIC_STACKFRAME 32 -#define _NUM_BYTES_EXTENDED_STACKFRAME 72 - -#define _SYSTEM_DCRDR_OFF 0x00 -#define _SYSTEM_DEMCR_OFF 0x04 - -#define _SYSTEM_DHCSR 0xE000EDF0 // Debug Halting Control and Status Register (DHCSR) -#define _SYSTEM_DCRSR 0xE000EDF4 // Debug Core Register Selector Register (DCRSR) -#define _SYSTEM_DCRDR 0xE000EDF8 // Debug Core Register Data Register (DCRDR) -#define _SYSTEM_DEMCR 0xE000EDFC // Debug Exception and Monitor Control Register (DEMCR) - -#define _SYSTEM_FPCCR 0xE000EF34 // Floating-Point Context Control Register (FPCCR) -#define _SYSTEM_FPCAR 0xE000EF38 // Floating-Point Context Address Register (FPCAR) -#define _SYSTEM_FPDSCR 0xE000EF3C // Floating-Point Default Status Control Register (FPDSCR) -#define _SYSTEM_MVFR0 0xE000EF40 // Media and FP Feature Register 0 (MVFR0) -#define _SYSTEM_MVFR1 0xE000EF44 // Media and FP Feature Register 1 (MVFR1) - -/* -* Defines for determining if the current debug config supports FPU registers -* For some compilers like IAR EWARM when disabling the FPU in the compiler settings an error is thrown when -*/ -#ifdef __FPU_PRESENT - #if __FPU_PRESENT - #define _HAS_FPU_REGS 1 - #else - #define _HAS_FPU_REGS 0 - #endif -#else - #define _HAS_FPU_REGS 0 -#endif - -/********************************************************************* -* -* Signature of monitor -* -* Function description -* Needed for targets where also a boot ROM is present that possibly specifies a vector table with a valid debug monitor exception entry -*/ - .section .text, "ax" - - // - // JLINKMONHANDLER - // - .byte 0x4A - .byte 0x4C - .byte 0x49 - .byte 0x4E - .byte 0x4B - .byte 0x4D - .byte 0x4F - .byte 0x4E - .byte 0x48 - .byte 0x41 - .byte 0x4E - .byte 0x44 - .byte 0x4C - .byte 0x45 - .byte 0x52 - .byte 0x00 // Align to 8-bytes - -/********************************************************************* -* -* DebugMon_Handler() -* -* Function description -* Debug monitor handler. CPU enters this handler in case a "halt" request is made from the debugger. -* This handler is also responsible for handling commands that are sent by the debugger. -* -* Notes -* This is actually the ISR for the debug interrupt (exception no. 12) -*/ - .thumb_func - -DebugMon_Handler: - /* - General procedure: - DCRDR is used as communication register - DEMCR[19] is used as ready flag - For the command J-Link sends to the monitor: DCRDR[7:0] == Cmd, DCRDR[31:8] == ParamData - - 1) Monitor sets DEMCR[19] whenever it is ready to receive new commands/data - DEMCR[19] is initially set on debug monitor entry - 2) J-Link will clear once it has placed conmmand/data in DCRDR for J-Link - 3) Monitor will wait for DEMCR[19] to be cleared - 4) Monitor will process command (May cause additional data transfers etc., depends on command - 5) No restart-CPU command? => Back to 2), Otherwise => 6) - 6) Monitor will clear DEMCR[19] 19 to indicate that it is no longer ready - */ - PUSH {LR} - BL JLINK_MONITOR_OnEnter - POP {LR} - LDR.N R3,_AddrDCRDR // 0xe000edf8 == _SYSTEM_DCRDR - B.N _IndicateMonReady -_WaitProbeReadIndicateMonRdy: // while(_SYSTEM_DEMCR & (1uL << 19)); => Wait until J-Link has read item - LDR R0,[R3, #+_SYSTEM_DEMCR_OFF] // _SYSTEM_DEMCR - LSLS R0,R0,#+12 - BMI.N _WaitProbeReadIndicateMonRdy -_IndicateMonReady: - LDR R0,[R3, #+_SYSTEM_DEMCR_OFF] // _SYSTEM_DEMCR |= (1uL << 19); => Set MON_REQ bit, so J-Link knows monitor is ready to receive commands - ORR R0,R0,#0x80000 - STR R0,[R3, #+_SYSTEM_DEMCR_OFF] - /* - During command loop: - R0 = Tmp - R1 = Tmp - R2 = Tmp - R3 = &_SYSTEM_DCRDR (allows also access to DEMCR with offset) - R12 = Tmp - - Outside command loop R0-R3 and R12 may be overwritten by MONITOR_OnPoll() - */ -_WaitForJLinkCmd: // do { - PUSH {LR} - BL JLINK_MONITOR_OnPoll - POP {LR} - LDR.N R3,_AddrDCRDR // 0xe000edf8 == _SYSTEM_DCRDR - LDR R0,[R3, #+_SYSTEM_DEMCR_OFF] - LSRS R0,R0,#+20 // DEMCR[19] -> Carry Clear? => J-Link has placed command for us - BCS _WaitForJLinkCmd - /* - Perform command - Command is placed by J-Link in DCRDR[7:0] and additional parameter data is stored in DCRDR[31:8] - J-Link clears DEMCR[19] to indicate that it placed a command/data or read data - Monitor sets DEMCR[19] to indicate that it placed data or read data / is ready for a new command - Setting DEMCR[19] indicates "monitor ready for new command / data" and also indicates: "data has been placed in DCRDR by monitor, for J-Link" - Therefore it is responsibility of the commands to respond to the commands accordingly - - Commands for debug monitor - Commands must not exceed 0xFF (255) as we only defined 8-bits for command-part. Higher 24-bits are parameter info for current command - - Protocol for different commands: - J-Link: Cmd -> DCRDR, DEMCR[19] -> 0 => Cmd placed by probe - */ - LDR R0,[R3, #+_SYSTEM_DCRDR_OFF] // ParamInfo = _SYSTEM_DCRDR - LSRS R1,R0,#+8 // ParamInfo >>= 8 - LSLS R0,R0,#+24 - LSRS R0,R0,#+24 // Cmd = ParamInfo & 0xFF - // - // switch (Cmd) - // - CMP R0,#+0 - BEQ.N _HandleGetMonVersion // case _MON_CMD_GET_MONITOR_VERSION - CMP R0,#+2 - BEQ.N _HandleReadReg // case _MON_CMD_READ_REG - BCC.N _HandleRestartCPU // case _MON_CMD_RESTART_CPU - CMP R0,#+3 - BEQ.N _HandleWriteReg_Veneer // case _MON_CMD_WRITE_REG - B.N _IndicateMonReady // default : while (1); - /* - Return - _MON_CMD_RESTART_CPU - CPU: DEMCR[19] -> 0 => Monitor no longer ready - */ -_HandleRestartCPU: - LDR R0,[R3, #+_SYSTEM_DEMCR_OFF] // _SYSTEM_DEMCR &= ~(1uL << 19); => Clear MON_REQ to indicate that monitor is no longer active - BIC R0,R0,#0x80000 - STR R0,[R3, #+_SYSTEM_DEMCR_OFF] - PUSH {LR} - BL JLINK_MONITOR_OnExit - POP {PC} - // - // Place data section here to not get in trouble with load-offsets - // - .section .text, "ax", %progbits - .align 2 -_AddrDCRDR: - .long 0xE000EDF8 -_AddrCPACR: - .long 0xE000ED88 - - .section .text, "ax" - .thumb_func - -;/********************************************************************* -;* -;* _HandleGetMonVersion -;* -;*/ -_HandleGetMonVersion: - /* - _MON_CMD_GET_MONITOR_VERSION - CPU: Data -> DCRDR, DEMCR[19] -> 1 => Data ready - J-Link: DCRDR -> Read, DEMCR[19] -> 0 => Data read - CPU: DEMCR[19] -> 1 => Mon ready - */ - MOVS R0,#+_MON_VERSION - STR R0,[R3, #+_SYSTEM_DCRDR_OFF] // _SYSTEM_DCRDR = x - LDR R0,[R3, #+_SYSTEM_DEMCR_OFF] // _SYSTEM_DEMCR |= (1uL << 19); => Set MON_REQ bit, so J-Link knows monitor is ready to receive commands - ORR R0,R0,#0x80000 - STR R0,[R3, #+_SYSTEM_DEMCR_OFF] // Indicate data ready - B _WaitProbeReadIndicateMonRdy - -/********************************************************************* -* -* _HandleReadReg -* -*/ -_HandleWriteReg_Veneer: - B.N _HandleWriteReg -_HandleReadReg: - /* - _MON_CMD_READ_REG - CPU: Data -> DCRDR, DEMCR[19] -> 1 => Data ready - J-Link: DCRDR -> Read, DEMCR[19] -> 0 => Data read - CPU: DEMCR[19] -> 1 => Mon ready - - - Register indexes - 0-15: R0-R15 (13 == R13 reserved => is banked ... Has to be read as PSP / MSP. Decision has to be done by J-Link DLL side!) - 16: XPSR - 17: MSP - 18: PSP - 19: CFBP CONTROL/FAULTMASK/BASEPRI/PRIMASK (packed into 4 bytes of word. CONTROL = CFBP[31:24], FAULTMASK = CFBP[16:23], BASEPRI = CFBP[15:8], PRIMASK = CFBP[7:0] - 20: FPSCR - 21-52: FPS0-FPS31 - - - Register usage when entering this "subroutine": - R0 Cmd - R1 ParamInfo - R2 --- - R3 = &_SYSTEM_DCRDR (allows also access to DEMCR with offset) - R12 --- - - Table B1-9 EXC_RETURN definition of exception return behavior, with FP extension - LR Return to Return SP Frame type - --------------------------------------------------------- - 0xFFFFFFE1 Handler mode. MSP Extended - 0xFFFFFFE9 Thread mode MSP Extended - 0xFFFFFFED Thread mode PSP Extended - 0xFFFFFFF1 Handler mode. MSP Basic - 0xFFFFFFF9 Thread mode MSP Basic - 0xFFFFFFFD Thread mode PSP Basic - - So LR[2] == 1 => Return stack == PSP else MSP - - R0-R3, R12, PC, xPSR can be read from application stackpointer - Other regs can be read directly - */ - LSRS R2,LR,#+3 // Shift LR[2] into carry => Carry clear means that CPU was running on MSP - ITE CS - MRSCS R2,PSP - MRSCC R2,MSP - CMP R1,#+4 // if (RegIndex < 4) { (R0-R3) - BCS _HandleReadRegR4 - LDR R0,[R2, R1, LSL #+2] // v = [SP + Rx * 4] (R0-R3) - B.N _HandleReadRegDone -_HandleReadRegR4: - CMP R1,#+5 // if (RegIndex < 5) { (R4) - BCS _HandleReadRegR5 - MOV R0,R4 - B.N _HandleReadRegDone -_HandleReadRegR5: - CMP R1,#+6 // if (RegIndex < 6) { (R5) - BCS _HandleReadRegR6 - MOV R0,R5 - B.N _HandleReadRegDone -_HandleReadRegR6: - CMP R1,#+7 // if (RegIndex < 7) { (R6) - BCS _HandleReadRegR7 - MOV R0,R6 - B.N _HandleReadRegDone -_HandleReadRegR7: - CMP R1,#+8 // if (RegIndex < 8) { (R7) - BCS _HandleReadRegR8 - MOV R0,R7 - B.N _HandleReadRegDone -_HandleReadRegR8: - CMP R1,#+9 // if (RegIndex < 9) { (R8) - BCS _HandleReadRegR9 - MOV R0,R8 - B.N _HandleReadRegDone -_HandleReadRegR9: - CMP R1,#+10 // if (RegIndex < 10) { (R9) - BCS _HandleReadRegR10 - MOV R0,R9 - B.N _HandleReadRegDone -_HandleReadRegR10: - CMP R1,#+11 // if (RegIndex < 11) { (R10) - BCS _HandleReadRegR11 - MOV R0,R10 - B.N _HandleReadRegDone -_HandleReadRegR11: - CMP R1,#+12 // if (RegIndex < 12) { (R11) - BCS _HandleReadRegR12 - MOV R0,R11 - B.N _HandleReadRegDone -_HandleReadRegR12: - CMP R1,#+14 // if (RegIndex < 14) { (R12) - BCS _HandleReadRegR14 - LDR R0,[R2, #+_APP_SP_OFF_R12] - B.N _HandleReadRegDone -_HandleReadRegR14: - CMP R1,#+15 // if (RegIndex < 15) { (R14 / LR) - BCS _HandleReadRegR15 - LDR R0,[R2, #+_APP_SP_OFF_R14_LR] - B.N _HandleReadRegDone -_HandleReadRegR15: - CMP R1,#+16 // if (RegIndex < 16) { (R15 / PC) - BCS _HandleReadRegXPSR - LDR R0,[R2, #+_APP_SP_OFF_PC] - B.N _HandleReadRegDone -_HandleReadRegXPSR: - CMP R1,#+17 // if (RegIndex < 17) { (xPSR) - BCS _HandleReadRegMSP - LDR R0,[R2, #+_APP_SP_OFF_XPSR] - B.N _HandleReadRegDone -_HandleReadRegMSP: - /* - Stackpointer is tricky because we need to get some info about the SP used in the user app, first - - Handle reading R0-R3 which can be read right from application stackpointer - - Table B1-9 EXC_RETURN definition of exception return behavior, with FP extension - LR Return to Return SP Frame type - --------------------------------------------------------- - 0xFFFFFFE1 Handler mode. MSP Extended - 0xFFFFFFE9 Thread mode MSP Extended - 0xFFFFFFED Thread mode PSP Extended - 0xFFFFFFF1 Handler mode. MSP Basic - 0xFFFFFFF9 Thread mode MSP Basic - 0xFFFFFFFD Thread mode PSP Basic - - So LR[2] == 1 => Return stack == PSP else MSP - Per architecture definition: Inside monitor (exception) SP = MSP - - Stack pointer handling is complicated because it is different what is pushed on the stack before entering the monitor ISR... - Cortex-M: 8 regs - Cortex-M + forced-stack-alignment: 8 regs + 1 dummy-word if stack was not 8-byte aligned - Cortex-M + FPU: 8 regs + 17 FPU regs + 1 dummy-word + 1-dummy word if stack was not 8-byte aligned - Cortex-M + FPU + lazy mode: 8 regs + 17 dummy-words + 1 dummy-word + 1-dummy word if stack was not 8-byte aligned - */ - CMP R1,#+18 // if (RegIndex < 18) { (MSP) - BCS _HandleReadRegPSP - MRS R0,MSP - LSRS R1,LR,#+3 // LR[2] -> Carry == 0 => CPU was running on MSP => Needs correction - BCS _HandleReadRegDone_Veneer // CPU was running on PSP? => No correction necessary -_HandleSPCorrection: - LSRS R1,LR,#+5 // LR[4] -> Carry == 0 => extended stack frame has been allocated. See ARM DDI0403D, B1.5.7 Stack alignment on exception entry - ITE CS - ADDCS R0,R0,#+_NUM_BYTES_BASIC_STACKFRAME - ADDCC R0,R0,#+_NUM_BYTES_EXTENDED_STACKFRAME - LDR R1,[R2, #+_APP_SP_OFF_XPSR] // Get xPSR from application stack (R2 has been set to app stack on beginning of _HandleReadReg) - LSRS R1,R1,#+5 // xPSR[9] -> Carry == 1 => Stack has been force-aligned before pushing regs. See ARM DDI0403D, B1.5.7 Stack alignment on exception entry - IT CS - ADDCS R0,R0,#+4 - B _HandleReadRegDone -_HandleReadRegPSP: // RegIndex == 18 - CMP R1,#+19 // if (RegIndex < 19) { - BCS _HandleReadRegCFBP - MRS R0,PSP // PSP is not touched by monitor - LSRS R1,LR,#+3 // LR[2] -> Carry == 1 => CPU was running on PSP => Needs correction - BCC _HandleReadRegDone_Veneer // CPU was running on MSP? => No correction of PSP necessary - B _HandleSPCorrection -_HandleReadRegCFBP: - /* - CFBP is a register that can only be read via debug probe and is a merger of the following regs: - CONTROL/FAULTMASK/BASEPRI/PRIMASK (packed into 4 bytes of word. CONTROL = CFBP[31:24], FAULTMASK = CFBP[16:23], BASEPRI = CFBP[15:8], PRIMASK = CFBP[7:0] - To keep J-Link side the same for monitor and halt mode, we also return CFBP in monitor mode - */ - CMP R1,#+20 // if (RegIndex < 20) { (CFBP) - BCS _HandleReadRegFPU - MOVS R0,#+0 - MRS R2,PRIMASK - ORRS R0,R2 // Merge PRIMASK into CFBP[7:0] - MRS R2,BASEPRI - LSLS R2,R2,#+8 // Merge BASEPRI into CFBP[15:8] - ORRS R0,R2 - MRS R2,FAULTMASK - LSLS R2,R2,#+16 // Merge FAULTMASK into CFBP[23:16] - ORRS R0,R2 - MRS R2,CONTROL - LSRS R1,LR,#3 // LR[2] -> Carry. CONTROL.SPSEL is saved to LR[2] on exception entry => ARM DDI0403D, B1.5.6 Exception entry behavior - IT CS // As J-Link sees value of CONTROL at application time, we need reconstruct original value of CONTROL - ORRCS R2,R2,#+2 // CONTROL.SPSEL (CONTROL[1]) == 0 inside monitor - LSRS R1,LR,#+5 // LR[4] == NOT(CONTROL.FPCA) -> Carry - ITE CS // Merge original value of FPCA (CONTROL[2]) into read data - BICCS R2,R2,#+0x04 // Remember LR contains NOT(CONTROL) - ORRCC R2,R2,#+0x04 - LSLS R2,R2,#+24 - ORRS R0,R2 - B.N _HandleReadRegDone -_HandleReadRegFPU: -#if _HAS_FPU_REGS - CMP R1,#+53 // if (RegIndex < 53) { (20 (FPSCR), 21-52 FPS0-FPS31) - BCS _HandleReadRegDone_Veneer - /* - Read Coprocessor Access Control Register (CPACR) to check if CP10 and CP11 are enabled - If not, access to floating point is not possible - CPACR[21:20] == CP10 enable. 0b01 = Privileged access only. 0b11 = Full access. Other = reserved - CPACR[23:22] == CP11 enable. 0b01 = Privileged access only. 0b11 = Full access. Other = reserved - */ - LDR R0,_AddrCPACR - LDR R0,[R0] - LSLS R0,R0,#+8 - LSRS R0,R0,#+28 - CMP R0,#+0xF - BEQ _HandleReadRegFPU_Allowed - CMP R0,#+0x5 - BNE _HandleReadRegDone_Veneer -_HandleReadRegFPU_Allowed: - CMP R1,#+21 // if (RegIndex < 21) (20 == FPSCR) - BCS _HandleReadRegFPS0_FPS31 - LSRS R0,LR,#+5 // CONTROL[2] == FPCA => NOT(FPCA) saved to LR[4]. LR[4] == 0 => Extended stack frame, so FPU regs possibly on stack - BCS _HandleReadFPSCRLazyMode // Remember: NOT(FPCA) is stored to LR. == 0 means: Extended stack frame - LDR R0,=_SYSTEM_FPCCR - LDR R0,[R0] - LSLS R0,R0,#+2 // FPCCR[30] -> Carry == 1 indicates if lazy mode is active, so space on stack is reserved but FPU registers are not saved on stack - BCS _HandleReadFPSCRLazyMode - LDR R0,[R2, #+_APP_SP_OFF_FPSCR] - B _HandleReadRegDone -_HandleReadFPSCRLazyMode: - VMRS R0,FPSCR - B _HandleReadRegDone -_HandleReadRegFPS0_FPS31: // RegIndex == 21-52 - LSRS R0,LR,#+5 // CONTROL[2] == FPCA => NOT(FPCA) saved to LR[4]. LR[4] == 0 => Extended stack frame, so FPU regs possibly on stack - BCS _HandleReadFPS0_FPS31LazyMode // Remember: NOT(FPCA) is stored to LR. == 0 means: Extended stack frame - LDR R0,=_SYSTEM_FPCCR - LDR R0,[R0] - LSLS R0,R0,#+2 // FPCCR[30] -> Carry == 1 indicates if lazy mode is active, so space on stack is reserved but FPU registers are not saved on stack - BCS _HandleReadFPS0_FPS31LazyMode - SUBS R1,#+21 // Convert absolute reg index into rel. one - LSLS R1,R1,#+2 // RegIndex to position on stack - ADDS R1,#+_APP_SP_OFF_S0 - LDR R0,[R2, R1] -_HandleReadRegDone_Veneer: - B _HandleReadRegDone -_HandleReadFPS0_FPS31LazyMode: - SUBS R1,#+20 // convert abs. RegIndex into rel. one - MOVS R0,#+6 - MULS R1,R0,R1 - LDR R0,=_HandleReadRegUnknown - SUB R0,R0,R1 // _HandleReadRegUnknown - 6 * ((RegIndex - 21) + 1) - ORR R0,R0,#1 // Thumb bit needs to be set in DestAddr - BX R0 - // - // Table for reading FPS0-FPS31 - // - VMOV R0,S31 // v = FPSx - B _HandleReadRegDone - VMOV R0,S30 - B _HandleReadRegDone - VMOV R0,S29 - B _HandleReadRegDone - VMOV R0,S28 - B _HandleReadRegDone - VMOV R0,S27 - B _HandleReadRegDone - VMOV R0,S26 - B _HandleReadRegDone - VMOV R0,S25 - B _HandleReadRegDone - VMOV R0,S24 - B _HandleReadRegDone - VMOV R0,S23 - B _HandleReadRegDone - VMOV R0,S22 - B _HandleReadRegDone - VMOV R0,S21 - B _HandleReadRegDone - VMOV R0,S20 - B _HandleReadRegDone - VMOV R0,S19 - B _HandleReadRegDone - VMOV R0,S18 - B _HandleReadRegDone - VMOV R0,S17 - B _HandleReadRegDone - VMOV R0,S16 - B _HandleReadRegDone - VMOV R0,S15 - B _HandleReadRegDone - VMOV R0,S14 - B _HandleReadRegDone - VMOV R0,S13 - B _HandleReadRegDone - VMOV R0,S12 - B _HandleReadRegDone - VMOV R0,S11 - B _HandleReadRegDone - VMOV R0,S10 - B _HandleReadRegDone - VMOV R0,S9 - B _HandleReadRegDone - VMOV R0,S8 - B _HandleReadRegDone - VMOV R0,S7 - B _HandleReadRegDone - VMOV R0,S6 - B _HandleReadRegDone - VMOV R0,S5 - B _HandleReadRegDone - VMOV R0,S4 - B _HandleReadRegDone - VMOV R0,S3 - B _HandleReadRegDone - VMOV R0,S2 - B _HandleReadRegDone - VMOV R0,S1 - B _HandleReadRegDone - VMOV R0,S0 - B _HandleReadRegDone -#else - B _HandleReadRegUnknown -_HandleReadRegDone_Veneer: - B _HandleReadRegDone -#endif -_HandleReadRegUnknown: - MOVS R0,#+0 // v = 0 - B.N _HandleReadRegDone -_HandleReadRegDone: - - // Send register content to J-Link and wait until J-Link has read the data - - STR R0,[R3, #+_SYSTEM_DCRDR_OFF] // DCRDR = v; - LDR R0,[R3, #+_SYSTEM_DEMCR_OFF] // _SYSTEM_DEMCR |= (1uL << 19); => Set MON_REQ bit, so J-Link knows monitor is ready to receive commands - ORR R0,R0,#0x80000 - STR R0,[R3, #+_SYSTEM_DEMCR_OFF] // Indicate data ready - B _WaitProbeReadIndicateMonRdy - - // Data section for register addresses - -_HandleWriteReg: - /* - _MON_CMD_WRITE_REG - CPU: DEMCR[19] -> 1 => Mon ready - J-Link: Data -> DCRDR, DEMCR[19] -> 0 => Data placed by probe - CPU: DCRDR -> Read, Process command, DEMCR[19] -> 1 => Data read & mon ready - - Register indexes - 0-15: R0-R15 (13 == R13 reserved => is banked ... Has to be read as PSP / MSP. Decision has to be done by J-Link DLL side!) - 16: XPSR - 17: MSP - 18: PSP - 19: CFBP CONTROL/FAULTMASK/BASEPRI/PRIMASK (packed into 4 bytes of word. CONTROL = CFBP[31:24], FAULTMASK = CFBP[16:23], BASEPRI = CFBP[15:8], PRIMASK = CFBP[7:0] - 20: FPSCR - 21-52: FPS0-FPS31 - - - Register usage when entering this "subroutine": - R0 Cmd - R1 ParamInfo - R2 --- - R3 = &_SYSTEM_DCRDR (allows also access to DEMCR with offset) - R12 --- - - Table B1-9 EXC_RETURN definition of exception return behavior, with FP extension - LR Return to Return SP Frame type - --------------------------------------------------------- - 0xFFFFFFE1 Handler mode. MSP Extended - 0xFFFFFFE9 Thread mode MSP Extended - 0xFFFFFFED Thread mode PSP Extended - 0xFFFFFFF1 Handler mode. MSP Basic - 0xFFFFFFF9 Thread mode MSP Basic - 0xFFFFFFFD Thread mode PSP Basic - - So LR[2] == 1 => Return stack == PSP else MSP - - R0-R3, R12, PC, xPSR can be written via application stackpointer - Other regs can be written directly - - - Read register data from J-Link into R0 - */ - LDR R0,[R3, #+_SYSTEM_DEMCR_OFF] // _SYSTEM_DEMCR |= (1uL << 19); => Monitor is ready to receive register data - ORR R0,R0,#0x80000 - STR R0,[R3, #+_SYSTEM_DEMCR_OFF] -_HandleWRegWaitUntilDataRecv: - LDR R0,[R3, #+_SYSTEM_DEMCR_OFF] - LSLS R0,R0,#+12 - BMI.N _HandleWRegWaitUntilDataRecv // DEMCR[19] == 0 => J-Link has placed new data for us - LDR R0,[R3, #+_SYSTEM_DCRDR_OFF] // Get register data - // - // Determine application SP - // - LSRS R2,LR,#+3 // Shift LR[2] into carry => Carry clear means that CPU was running on MSP - ITE CS - MRSCS R2,PSP - MRSCC R2,MSP - CMP R1,#+4 // if (RegIndex < 4) { (R0-R3) - BCS _HandleWriteRegR4 - STR R0,[R2, R1, LSL #+2] // v = [SP + Rx * 4] (R0-R3) - B.N _HandleWriteRegDone -_HandleWriteRegR4: - CMP R1,#+5 // if (RegIndex < 5) { (R4) - BCS _HandleWriteRegR5 - MOV R4,R0 - B.N _HandleWriteRegDone -_HandleWriteRegR5: - CMP R1,#+6 // if (RegIndex < 6) { (R5) - BCS _HandleWriteRegR6 - MOV R5,R0 - B.N _HandleWriteRegDone -_HandleWriteRegR6: - CMP R1,#+7 // if (RegIndex < 7) { (R6) - BCS _HandleWriteRegR7 - MOV R6,R0 - B.N _HandleWriteRegDone -_HandleWriteRegR7: - CMP R1,#+8 // if (RegIndex < 8) { (R7) - BCS _HandleWriteRegR8 - MOV R7,R0 - B.N _HandleWriteRegDone -_HandleWriteRegR8: - CMP R1,#+9 // if (RegIndex < 9) { (R8) - BCS _HandleWriteRegR9 - MOV R8,R0 - B.N _HandleWriteRegDone -_HandleWriteRegR9: - CMP R1,#+10 // if (RegIndex < 10) { (R9) - BCS _HandleWriteRegR10 - MOV R9,R0 - B.N _HandleWriteRegDone -_HandleWriteRegR10: - CMP R1,#+11 // if (RegIndex < 11) { (R10) - BCS _HandleWriteRegR11 - MOV R10,R0 - B.N _HandleWriteRegDone -_HandleWriteRegR11: - CMP R1,#+12 // if (RegIndex < 12) { (R11) - BCS _HandleWriteRegR12 - MOV R11,R0 - B.N _HandleWriteRegDone -_HandleWriteRegR12: - CMP R1,#+14 // if (RegIndex < 14) { (R12) - BCS _HandleWriteRegR14 - STR R0,[R2, #+_APP_SP_OFF_R12] - B.N _HandleWriteRegDone -_HandleWriteRegR14: - CMP R1,#+15 // if (RegIndex < 15) { (R14 / LR) - BCS _HandleWriteRegR15 - STR R0,[R2, #+_APP_SP_OFF_R14_LR] - B.N _HandleWriteRegDone -_HandleWriteRegR15: - CMP R1,#+16 // if (RegIndex < 16) { (R15 / PC) - BCS _HandleWriteRegXPSR - STR R0,[R2, #+_APP_SP_OFF_PC] - B.N _HandleWriteRegDone -_HandleWriteRegXPSR: - CMP R1,#+17 // if (RegIndex < 17) { (xPSR) - BCS _HandleWriteRegMSP - STR R0,[R2, #+_APP_SP_OFF_XPSR] - B.N _HandleWriteRegDone -_HandleWriteRegMSP: - // - // For now, SP cannot be modified because it is needed to jump back from monitor mode - // - CMP R1,#+18 // if (RegIndex < 18) { (MSP) - BCS _HandleWriteRegPSP - B.N _HandleWriteRegDone -_HandleWriteRegPSP: // RegIndex == 18 - CMP R1,#+19 // if (RegIndex < 19) { - BCS _HandleWriteRegCFBP - B.N _HandleWriteRegDone -_HandleWriteRegCFBP: - /* - CFBP is a register that can only be read via debug probe and is a merger of the following regs: - CONTROL/FAULTMASK/BASEPRI/PRIMASK (packed into 4 bytes of word. CONTROL = CFBP[31:24], FAULTMASK = CFBP[16:23], BASEPRI = CFBP[15:8], PRIMASK = CFBP[7:0] - To keep J-Link side the same for monitor and halt mode, we also return CFBP in monitor mode - */ - CMP R1,#+20 // if (RegIndex < 20) { (CFBP) - BCS _HandleWriteRegFPU - LSLS R1,R0,#+24 - LSRS R1,R1,#+24 // Extract CFBP[7:0] => PRIMASK - MSR PRIMASK,R1 - LSLS R1,R0,#+16 - LSRS R1,R1,#+24 // Extract CFBP[15:8] => BASEPRI - MSR BASEPRI,R1 - LSLS R1,R0,#+8 // Extract CFBP[23:16] => FAULTMASK - LSRS R1,R1,#+24 - MSR FAULTMASK,R1 - LSRS R1,R0,#+24 // Extract CFBP[31:24] => CONTROL - LSRS R0,R1,#2 // Current CONTROL[1] -> Carry - ITE CS // Update saved CONTROL.SPSEL (CONTROL[1]). CONTROL.SPSEL is saved to LR[2] on exception entry => ARM DDI0403D, B1.5.6 Exception entry behavior - ORRCS LR,LR,#+4 - BICCC LR,LR,#+4 - BIC R1,R1,#+2 // CONTROL.SPSEL (CONTROL[1]) == 0 inside monitor. Otherwise behavior is UNPREDICTABLE - LSRS R0,R1,#+3 // New CONTROL.FPCA (CONTROL[2]) -> Carry - ITE CS // CONTROL[2] == FPCA => NOT(FPCA) saved to LR[4]. LR[4] == 0 => Extended stack frame, so FPU regs possibly on stack - BICCS LR,LR,#+0x10 // Remember: NOT(FPCA) is stored to LR. == 0 means: Extended stack frame - ORRCC LR,LR,#+0x10 - MRS R0,CONTROL - LSRS R0,R0,#+3 // CONTROL[2] -> Carry - ITE CS // Preserve original value of current CONTROL[2] - ORRCS R1,R1,#+0x04 - BICCC R1,R1,#+0x04 - MSR CONTROL,R1 - ISB // Necessary after writing to CONTROL, see ARM DDI0403D, B1.4.4 The special-purpose CONTROL register - B.N _HandleWriteRegDone -_HandleWriteRegFPU: -#if _HAS_FPU_REGS - CMP R1,#+53 // if (RegIndex < 53) { (20 (FPSCR), 21-52 FPS0-FPS31) - BCS _HandleWriteRegDone_Veneer - /* - Read Coprocessor Access Control Register (CPACR) to check if CP10 and CP11 are enabled - If not, access to floating point is not possible - CPACR[21:20] == CP10 enable. 0b01 = Privileged access only. 0b11 = Full access. Other = reserved - CPACR[23:22] == CP11 enable. 0b01 = Privileged access only. 0b11 = Full access. Other = reserved - */ - MOV R12,R0 // Save register data - LDR R0,_AddrCPACR - LDR R0,[R0] - LSLS R0,R0,#+8 - LSRS R0,R0,#+28 - CMP R0,#+0xF - BEQ _HandleWriteRegFPU_Allowed - CMP R0,#+0x5 - BNE _HandleWriteRegDone_Veneer -_HandleWriteRegFPU_Allowed: - CMP R1,#+21 // if (RegIndex < 21) (20 == FPSCR) - BCS _HandleWriteRegFPS0_FPS31 - LSRS R0,LR,#+5 // CONTROL[2] == FPCA => NOT(FPCA) saved to LR[4]. LR[4] == 0 => Extended stack frame, so FPU regs possibly on stack - BCS _HandleWriteFPSCRLazyMode // Remember: NOT(FPCA) is stored to LR. == 0 means: Extended stack frame - LDR R0,=_SYSTEM_FPCCR - LDR R0,[R0] - LSLS R0,R0,#+2 // FPCCR[30] -> Carry == 1 indicates if lazy mode is active, so space on stack is reserved but FPU registers are not saved on stack - BCS _HandleWriteFPSCRLazyMode - STR R12,[R2, #+_APP_SP_OFF_FPSCR] - B _HandleWriteRegDone -_HandleWriteFPSCRLazyMode: - VMSR FPSCR,R12 - B _HandleWriteRegDone -_HandleWriteRegFPS0_FPS31: // RegIndex == 21-52 - LDR R0,=_SYSTEM_FPCCR - LDR R0,[R0] - LSLS R0,R0,#+2 // FPCCR[30] -> Carry == 1 indicates if lazy mode is active, so space on stack is reserved but FPU registers are not saved on stack - BCS _HandleWriteFPS0_FPS31LazyMode - LSRS R0,LR,#+5 // CONTROL[2] == FPCA => NOT(FPCA) saved to LR[4]. LR[4] == 0 => Extended stack frame, so FPU regs possibly on stack - BCS _HandleWriteFPS0_FPS31LazyMode // Remember: NOT(FPCA) is stored to LR. == 0 means: Extended stack frame - SUBS R1,#+21 // Convert absolute reg index into rel. one - LSLS R1,R1,#+2 // RegIndex to position on stack - ADDS R1,#+_APP_SP_OFF_S0 - STR R12,[R2, R1] -_HandleWriteRegDone_Veneer: - B _HandleWriteRegDone -_HandleWriteFPS0_FPS31LazyMode: - SUBS R1,#+20 // Convert abs. RegIndex into rel. one - MOVS R0,#+6 - MULS R1,R0,R1 - LDR R0,=_HandleReadRegUnknown - SUB R0,R0,R1 // _HandleReadRegUnknown - 6 * ((RegIndex - 21) + 1) - ORR R0,R0,#1 // Thumb bit needs to be set in DestAddr - BX R0 - // - // Table for reading FPS0-FPS31 - // - VMOV S31,R12 // v = FPSx - B _HandleWriteRegDone - VMOV S30,R12 - B _HandleWriteRegDone - VMOV S29,R12 - B _HandleWriteRegDone - VMOV S28,R12 - B _HandleWriteRegDone - VMOV S27,R12 - B _HandleWriteRegDone - VMOV S26,R12 - B _HandleWriteRegDone - VMOV S25,R12 - B _HandleWriteRegDone - VMOV S24,R12 - B _HandleWriteRegDone - VMOV S23,R12 - B _HandleWriteRegDone - VMOV S22,R12 - B _HandleWriteRegDone - VMOV S21,R12 - B _HandleWriteRegDone - VMOV S20,R12 - B _HandleWriteRegDone - VMOV S19,R12 - B _HandleWriteRegDone - VMOV S18,R12 - B _HandleWriteRegDone - VMOV S17,R12 - B _HandleWriteRegDone - VMOV S16,R12 - B _HandleWriteRegDone - VMOV S15,R12 - B _HandleWriteRegDone - VMOV S14,R12 - B _HandleWriteRegDone - VMOV S13,R12 - B _HandleWriteRegDone - VMOV S12,R12 - B _HandleWriteRegDone - VMOV S11,R12 - B _HandleWriteRegDone - VMOV S10,R12 - B _HandleWriteRegDone - VMOV S9,R12 - B _HandleWriteRegDone - VMOV S8,R12 - B _HandleWriteRegDone - VMOV S7,R12 - B _HandleWriteRegDone - VMOV S6,R12 - B _HandleWriteRegDone - VMOV S5,R12 - B _HandleWriteRegDone - VMOV S4,R12 - B _HandleWriteRegDone - VMOV S3,R12 - B _HandleWriteRegDone - VMOV S2,R12 - B _HandleWriteRegDone - VMOV S1,R12 - B _HandleWriteRegDone - VMOV S0,R12 - B _HandleWriteRegDone -#else - B _HandleWriteRegUnknown -#endif -_HandleWriteRegUnknown: - B.N _HandleWriteRegDone -_HandleWriteRegDone: - B _IndicateMonReady // Indicate that monitor has read data, processed command and is ready for a new one - .end -/****** End Of File *************************************************/ From 0952d1b2526edb795495548b8e53ce98f5f65829 Mon Sep 17 00:00:00 2001 From: medentem <122332405+medentem@users.noreply.github.com> Date: Sun, 6 Oct 2024 02:32:07 -0500 Subject: [PATCH 67/88] UserPrefs - Preconfigure up to 3 channels, GPS Mode (#4930) * added up to 3 channels via userprefs * added up to 3 channels via userprefs * added up to 3 channels via userprefs * trunk fmt * Added USERPREFS for GPS MODE --- src/mesh/Channels.cpp | 82 +++++++++++++++++++++++++++++++++---------- src/mesh/Channels.h | 7 +++- src/mesh/NodeDB.cpp | 4 ++- userPrefs.h | 22 ++++++++++++ 4 files changed, 94 insertions(+), 21 deletions(-) diff --git a/src/mesh/Channels.cpp b/src/mesh/Channels.cpp index c8ac09a37..bb30e501d 100644 --- a/src/mesh/Channels.cpp +++ b/src/mesh/Channels.cpp @@ -76,6 +76,23 @@ meshtastic_Channel &Channels::fixupChannel(ChannelIndex chIndex) return ch; } +void Channels::initDefaultLoraConfig() +{ + meshtastic_Config_LoRaConfig &loraConfig = config.lora; + + loraConfig.modem_preset = meshtastic_Config_LoRaConfig_ModemPreset_LONG_FAST; // Default to Long Range & Fast + loraConfig.use_preset = true; + loraConfig.tx_power = 0; // default + loraConfig.channel_num = 0; + +#ifdef USERPREFS_LORACONFIG_MODEM_PRESET + loraConfig.modem_preset = USERPREFS_LORACONFIG_MODEM_PRESET; +#endif +#ifdef USERPREFS_LORACONFIG_CHANNEL_NUM + loraConfig.channel_num = USERPREFS_LORACONFIG_CHANNEL_NUM; +#endif +} + /** * Write a default channel to the specified channel index */ @@ -83,12 +100,7 @@ void Channels::initDefaultChannel(ChannelIndex chIndex) { meshtastic_Channel &ch = getByIndex(chIndex); meshtastic_ChannelSettings &channelSettings = ch.settings; - meshtastic_Config_LoRaConfig &loraConfig = config.lora; - loraConfig.modem_preset = meshtastic_Config_LoRaConfig_ModemPreset_LONG_FAST; // Default to Long Range & Fast - loraConfig.use_preset = true; - loraConfig.tx_power = 0; // default - loraConfig.channel_num = 0; uint8_t defaultpskIndex = 1; channelSettings.psk.bytes[0] = defaultpskIndex; channelSettings.psk.size = 1; @@ -97,21 +109,14 @@ void Channels::initDefaultChannel(ChannelIndex chIndex) channelSettings.has_module_settings = true; ch.has_settings = true; - ch.role = meshtastic_Channel_Role_PRIMARY; + ch.role = chIndex == 0 ? meshtastic_Channel_Role_PRIMARY : meshtastic_Channel_Role_SECONDARY; -#ifdef USERPREFS_LORACONFIG_MODEM_PRESET - loraConfig.modem_preset = USERPREFS_LORACONFIG_MODEM_PRESET; -#endif -#ifdef USERPREFS_LORACONFIG_CHANNEL_NUM - loraConfig.channel_num = USERPREFS_LORACONFIG_CHANNEL_NUM; -#endif - - // Install custom defaults. Will eventually support setting multiple default channels - if (chIndex == 0) { + switch (chIndex) { + case 0: #ifdef USERPREFS_CHANNEL_0_PSK - static const uint8_t defaultpsk[] = USERPREFS_CHANNEL_0_PSK; - memcpy(channelSettings.psk.bytes, defaultpsk, sizeof(defaultpsk)); - channelSettings.psk.size = sizeof(defaultpsk); + static const uint8_t defaultpsk0[] = USERPREFS_CHANNEL_0_PSK; + memcpy(channelSettings.psk.bytes, defaultpsk0, sizeof(defaultpsk0)); + channelSettings.psk.size = sizeof(defaultpsk0); #endif #ifdef USERPREFS_CHANNEL_0_NAME @@ -120,6 +125,37 @@ void Channels::initDefaultChannel(ChannelIndex chIndex) #ifdef USERPREFS_CHANNEL_0_PRECISION channelSettings.module_settings.position_precision = USERPREFS_CHANNEL_0_PRECISION; #endif + break; + case 1: +#ifdef USERPREFS_CHANNEL_1_PSK + static const uint8_t defaultpsk1[] = USERPREFS_CHANNEL_1_PSK; + memcpy(channelSettings.psk.bytes, defaultpsk1, sizeof(defaultpsk1)); + channelSettings.psk.size = sizeof(defaultpsk1); + +#endif +#ifdef USERPREFS_CHANNEL_1_NAME + strcpy(channelSettings.name, USERPREFS_CHANNEL_1_NAME); +#endif +#ifdef USERPREFS_CHANNEL_1_PRECISION + channelSettings.module_settings.position_precision = USERPREFS_CHANNEL_1_PRECISION; +#endif + break; + case 2: +#ifdef USERPREFS_CHANNEL_2_PSK + static const uint8_t defaultpsk2[] = USERPREFS_CHANNEL_2_PSK; + memcpy(channelSettings.psk.bytes, defaultpsk2, sizeof(defaultpsk2)); + channelSettings.psk.size = sizeof(defaultpsk2); + +#endif +#ifdef USERPREFS_CHANNEL_2_NAME + strcpy(channelSettings.name, USERPREFS_CHANNEL_2_NAME); +#endif +#ifdef USERPREFS_CHANNEL_2_PRECISION + channelSettings.module_settings.position_precision = USERPREFS_CHANNEL_2_PRECISION; +#endif + break; + default: + break; } } @@ -209,7 +245,15 @@ void Channels::initDefaults() channelFile.channels_count = MAX_NUM_CHANNELS; for (int i = 0; i < channelFile.channels_count; i++) fixupChannel(i); + initDefaultLoraConfig(); + +#ifdef USERPREFS_CHANNELS_TO_WRITE + for (int i = 0; i < USERPREFS_CHANNELS_TO_WRITE; i++) { + initDefaultChannel(i); + } +#else initDefaultChannel(0); +#endif } void Channels::onConfigChanged() @@ -359,4 +403,4 @@ bool Channels::decryptForHash(ChannelIndex chIndex, ChannelHash channelHash) int16_t Channels::setActiveByIndex(ChannelIndex channelIndex) { return setCrypto(channelIndex); -} +} \ No newline at end of file diff --git a/src/mesh/Channels.h b/src/mesh/Channels.h index e5a750f71..b0c9b3d07 100644 --- a/src/mesh/Channels.h +++ b/src/mesh/Channels.h @@ -117,7 +117,12 @@ class Channels meshtastic_Channel &fixupChannel(ChannelIndex chIndex); /** - * Write a default channel to the specified channel index + * Writes the default lora config + */ + void initDefaultLoraConfig(); + + /** + * Write default channels defined in UserPrefs */ void initDefaultChannel(ChannelIndex chIndex); diff --git a/src/mesh/NodeDB.cpp b/src/mesh/NodeDB.cpp index d947f0cea..49f0cbc62 100644 --- a/src/mesh/NodeDB.cpp +++ b/src/mesh/NodeDB.cpp @@ -336,7 +336,9 @@ void NodeDB::installDefaultConfig(bool preserveKey = false) #else config.device.disable_triple_click = true; #endif -#if !HAS_GPS || defined(T_DECK) || defined(TLORA_T3S3_EPAPER) +#if defined(USERPREFS_CONFIG_GPS_MODE) + config.position.gps_mode = USERPREFS_CONFIG_GPS_MODE; +#elif !HAS_GPS || defined(T_DECK) || defined(TLORA_T3S3_EPAPER) config.position.gps_mode = meshtastic_Config_PositionConfig_GpsMode_NOT_PRESENT; #elif !defined(GPS_RX_PIN) if (config.position.rx_gpio == 0) diff --git a/userPrefs.h b/userPrefs.h index f544a6535..ed622bcfb 100644 --- a/userPrefs.h +++ b/userPrefs.h @@ -13,6 +13,10 @@ // #define USERPREFS_LORACONFIG_MODEM_PRESET meshtastic_Config_LoRaConfig_ModemPreset_SHORT_FAST // #define USERPREFS_LORACONFIG_CHANNEL_NUM 31 // #define USERPREFS_CONFIG_LORA_IGNORE_MQTT true + +// #define USERPREFS_CONFIG_GPS_MODE meshtastic_Config_PositionConfig_GpsMode_ENABLED + +// #define USERPREFS_CHANNELS_TO_WRITE 3 /* #define USERPREFS_CHANNEL_0_PSK \ { \ @@ -22,6 +26,24 @@ */ // #define USERPREFS_CHANNEL_0_NAME "DEFCONnect" // #define USERPREFS_CHANNEL_0_PRECISION 14 +/* +#define USERPREFS_CHANNEL_1_PSK \ + { \ + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, \ + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 \ + } +*/ +// #define USERPREFS_CHANNEL_1_NAME "REPLACEME" +// #define USERPREFS_CHANNEL_1_PRECISION 14 +/* +#define USERPREFS_CHANNEL_2_PSK \ + { \ + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, \ + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 \ + } +*/ +// #define USERPREFS_CHANNEL_2_NAME "REPLACEME" +// #define USERPREFS_CHANNEL_2_PRECISION 14 // #define USERPREFS_CONFIG_OWNER_LONG_NAME "My Long Name" // #define USERPREFS_CONFIG_OWNER_SHORT_NAME "MLN" From a3a97d3025822c38256a560d1eb83695e2b589f1 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Sun, 6 Oct 2024 05:24:57 -0500 Subject: [PATCH 68/88] Start of generating json manifest of macros in userPrefs.h (#4946) * Start of generating json manifest for userPrefs.h * Just trunk this for now * Add automatic generation of json manifest in GH action * Trunk --- .github/workflows/generate-userprefs.yml | 33 ++++++++++++++++ bin/build-userprefs-json.py | 48 ++++++++++++++++++++++++ userPrefs.json | 16 ++++++++ 3 files changed, 97 insertions(+) create mode 100644 .github/workflows/generate-userprefs.yml create mode 100644 bin/build-userprefs-json.py create mode 100644 userPrefs.json diff --git a/.github/workflows/generate-userprefs.yml b/.github/workflows/generate-userprefs.yml new file mode 100644 index 000000000..9c4c75569 --- /dev/null +++ b/.github/workflows/generate-userprefs.yml @@ -0,0 +1,33 @@ +on: + push: + paths: + - userPrefs.h + branches: + - master + +jobs: + generate-userprefs: + runs-on: ubuntu-latest + steps: + - name: Checkout code + uses: actions/checkout@v4 + + - name: Install Clang + run: sudo apt-get install -y clang + + - name: Install trunk + run: curl https://get.trunk.io -fsSL | bash + + - name: Generate userPrefs.jsom + run: python3 ./bin/build-userprefs-json.py + + - name: Trunk format json + run: trunk format userPrefs.json + + - name: Commit userPrefs.json + run: | + git config --global user.email "actions@github.com" + git config --global user.name "GitHub Actions" + git add userPrefs.json + git commit -m "Update userPrefs.json" + git push diff --git a/bin/build-userprefs-json.py b/bin/build-userprefs-json.py new file mode 100644 index 000000000..58f460bcf --- /dev/null +++ b/bin/build-userprefs-json.py @@ -0,0 +1,48 @@ +import json +import subprocess +import re + +def get_macros_from_header(header_file): + # Run clang to preprocess the header file and capture the output + result = subprocess.run(['clang', '-E', '-dM', header_file], capture_output=True, text=True) + if result.returncode != 0: + raise RuntimeError(f"Clang preprocessing failed: {result.stderr}") + + # Extract macros from the output + macros = {} + macro_pattern = re.compile(r'#define\s+(\w+)\s+(.*)') + for line in result.stdout.splitlines(): + match = macro_pattern.match(line) + if match and 'USERPREFS_' in line and '_USERPREFS_' not in line: + macros[match.group(1)] = match.group(2) + + return macros + +def write_macros_to_json(macros, output_file): + with open(output_file, 'w') as f: + json.dump(macros, f, indent=4) + +def main(): + header_file = 'userPrefs.h' + output_file = 'userPrefs.json' + # Uncomment all macros in the header file + with open(header_file, 'r') as file: + lines = file.readlines() + + uncommented_lines = [] + for line in lines: + stripped_line = line.strip().replace('/*', '').replace('*/', '') + if stripped_line.startswith('//') and 'USERPREFS_' in stripped_line: + # Replace "//" + stripped_line = stripped_line.replace('//', '') + uncommented_lines.append(stripped_line + '\n') + + with open(header_file, 'w') as file: + for line in uncommented_lines: + file.write(line) + macros = get_macros_from_header(header_file) + write_macros_to_json(macros, output_file) + print(f"Macros have been written to {output_file}") + +if __name__ == "__main__": + main() \ No newline at end of file diff --git a/userPrefs.json b/userPrefs.json new file mode 100644 index 000000000..bc62602be --- /dev/null +++ b/userPrefs.json @@ -0,0 +1,16 @@ +{ + "USERPREFS_CHANNEL_0_NAME": "\"DEFCONnect\"", + "USERPREFS_CHANNEL_0_PRECISION": "14", + "USERPREFS_CHANNEL_0_PSK": "{ 0x38, 0x4b, 0xbc, 0xc0, 0x1d, 0xc0, 0x22, 0xd1, 0x81, 0xbf, 0x36, 0xb8, 0x61, 0x21, 0xe1, 0xfb, 0x96, 0xb7, 0x2e, 0x55, 0xbf, 0x74, 0x22, 0x7e, 0x9d, 0x6a, 0xfb, 0x48, 0xd6, 0x4c, 0xb1, 0xa1 }", + "USERPREFS_CONFIG_LORA_IGNORE_MQTT": "true", + "USERPREFS_CONFIG_LORA_REGION": "meshtastic_Config_LoRaConfig_RegionCode_US", + "USERPREFS_CONFIG_OWNER_LONG_NAME": "\"My Long Name\"", + "USERPREFS_CONFIG_OWNER_SHORT_NAME": "\"MLN\"", + "USERPREFS_EVENT_MODE": "1", + "USERPREFS_HAS_SPLASH": "", + "USERPREFS_LORACONFIG_CHANNEL_NUM": "31", + "USERPREFS_LORACONFIG_MODEM_PRESET": "meshtastic_Config_LoRaConfig_ModemPreset_SHORT_FAST", + "USERPREFS_SPLASH_TITLE": "\"DEFCONtastic\"", + "USERPREFS_TZ_STRING": "\"tzplaceholder \"", + "USERPREFS_USE_ADMIN_KEY": "1" +} From 01df3ff4775c4ef368b71d4b64d15252c891fb68 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Sun, 6 Oct 2024 05:26:04 -0500 Subject: [PATCH 69/88] Update generate-userprefs.yml --- .github/workflows/generate-userprefs.yml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/.github/workflows/generate-userprefs.yml b/.github/workflows/generate-userprefs.yml index 9c4c75569..10dd1ff7d 100644 --- a/.github/workflows/generate-userprefs.yml +++ b/.github/workflows/generate-userprefs.yml @@ -1,3 +1,5 @@ +name: Generate UsersPrefs JSON manifest + on: push: paths: From 553e572eb52575726939b3cc309047f04ea0930b Mon Sep 17 00:00:00 2001 From: Tom Fifield Date: Sun, 6 Oct 2024 19:40:06 +0800 Subject: [PATCH 70/88] Coalesce duplicated method GetTimeSinceMeshPacket (#4968) GetTimeSinceMeshPacket was duplicated in PowerTelemetry and EnvironmentalTelemetry, albeit one had a cooler name than the other. As we add HealthTelemetry, to avoid creating a third instance of this method, let's move it somewhere that makese sense. Adds a new method GetTimeSinceMeshPacket to MeshService and updates EnvironmentTelemetry and PowerTelemetry to use it. --- src/mesh/MeshService.cpp | 14 +++++++++++++- src/mesh/MeshService.h | 4 +++- src/modules/Telemetry/EnvironmentTelemetry.cpp | 16 ++-------------- src/modules/Telemetry/PowerTelemetry.cpp | 16 ++-------------- 4 files changed, 20 insertions(+), 30 deletions(-) diff --git a/src/mesh/MeshService.cpp b/src/mesh/MeshService.cpp index a8a207352..655348bd5 100644 --- a/src/mesh/MeshService.cpp +++ b/src/mesh/MeshService.cpp @@ -406,4 +406,16 @@ int MeshService::onGPSChanged(const meshtastic::GPSStatus *newStatus) bool MeshService::isToPhoneQueueEmpty() { return toPhoneQueue.isEmpty(); -} \ No newline at end of file +} + +uint32_t MeshService::GetTimeSinceMeshPacket(const meshtastic_MeshPacket *mp) +{ + uint32_t now = getTime(); + + uint32_t last_seen = mp->rx_time; + int delta = (int)(now - last_seen); + if (delta < 0) // our clock must be slightly off still - not set from GPS yet + delta = 0; + + return delta; +} diff --git a/src/mesh/MeshService.h b/src/mesh/MeshService.h index b91fedada..1ccca4e6d 100644 --- a/src/mesh/MeshService.h +++ b/src/mesh/MeshService.h @@ -151,6 +151,8 @@ class MeshService ErrorCode sendQueueStatusToPhone(const meshtastic_QueueStatus &qs, ErrorCode res, uint32_t mesh_packet_id); + uint32_t GetTimeSinceMeshPacket(const meshtastic_MeshPacket *mp); + private: #if HAS_GPS /// Called when our gps position has changed - updates nodedb and sends Location message out into the mesh @@ -163,4 +165,4 @@ class MeshService friend class RoutingModule; }; -extern MeshService *service; \ No newline at end of file +extern MeshService *service; diff --git a/src/modules/Telemetry/EnvironmentTelemetry.cpp b/src/modules/Telemetry/EnvironmentTelemetry.cpp index ac291c4ab..147f4ed34 100644 --- a/src/modules/Telemetry/EnvironmentTelemetry.cpp +++ b/src/modules/Telemetry/EnvironmentTelemetry.cpp @@ -187,18 +187,6 @@ float EnvironmentTelemetryModule::CelsiusToFahrenheit(float c) return (c * 9) / 5 + 32; } -uint32_t GetTimeSinceMeshPacket(const meshtastic_MeshPacket *mp) -{ - uint32_t now = getTime(); - - uint32_t last_seen = mp->rx_time; - int delta = (int)(now - last_seen); - if (delta < 0) // our clock must be slightly off still - not set from GPS yet - delta = 0; - - return delta; -} - void EnvironmentTelemetryModule::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y) { display->setTextAlignment(TEXT_ALIGN_LEFT); @@ -213,7 +201,7 @@ void EnvironmentTelemetryModule::drawFrame(OLEDDisplay *display, OLEDDisplayUiSt // Decode the last measurement packet meshtastic_Telemetry lastMeasurement; - uint32_t agoSecs = GetTimeSinceMeshPacket(lastMeasurementPacket); + uint32_t agoSecs = service->GetTimeSinceMeshPacket(lastMeasurementPacket); const char *lastSender = getSenderShortName(*lastMeasurementPacket); const meshtastic_Data &p = lastMeasurementPacket->decoded; @@ -601,4 +589,4 @@ AdminMessageHandleResult EnvironmentTelemetryModule::handleAdminMessageForModule return result; } -#endif \ No newline at end of file +#endif diff --git a/src/modules/Telemetry/PowerTelemetry.cpp b/src/modules/Telemetry/PowerTelemetry.cpp index 038cbfadc..be3048998 100644 --- a/src/modules/Telemetry/PowerTelemetry.cpp +++ b/src/modules/Telemetry/PowerTelemetry.cpp @@ -94,18 +94,6 @@ bool PowerTelemetryModule::wantUIFrame() return moduleConfig.telemetry.power_screen_enabled; } -uint32_t GetTimeyWimeySinceMeshPacket(const meshtastic_MeshPacket *mp) -{ - uint32_t now = getTime(); - - uint32_t last_seen = mp->rx_time; - int delta = (int)(now - last_seen); - if (delta < 0) // our clock must be slightly off still - not set from GPS yet - delta = 0; - - return delta; -} - void PowerTelemetryModule::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y) { display->setTextAlignment(TEXT_ALIGN_LEFT); @@ -119,7 +107,7 @@ void PowerTelemetryModule::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *s meshtastic_Telemetry lastMeasurement; - uint32_t agoSecs = GetTimeyWimeySinceMeshPacket(lastMeasurementPacket); + uint32_t agoSecs = service->GetTimeSinceMeshPacket(lastMeasurementPacket); const char *lastSender = getSenderShortName(*lastMeasurementPacket); const meshtastic_Data &p = lastMeasurementPacket->decoded; @@ -265,4 +253,4 @@ bool PowerTelemetryModule::sendTelemetry(NodeNum dest, bool phoneOnly) return false; } -#endif \ No newline at end of file +#endif From ebc3a66d109d9c3b49031f23d424c8e09a989c16 Mon Sep 17 00:00:00 2001 From: Tom Fifield Date: Sun, 6 Oct 2024 19:40:23 +0800 Subject: [PATCH 71/88] Which Module wants a UI Frame? (#4967) Previously our debug message for screens blandly stated "Module wants a UI Frame" This patch replaces the word Module with the name of the Module in need of a frame a frame, enhancing debugging ability. --- src/mesh/MeshModule.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/mesh/MeshModule.cpp b/src/mesh/MeshModule.cpp index 27aca5832..c60404c98 100644 --- a/src/mesh/MeshModule.cpp +++ b/src/mesh/MeshModule.cpp @@ -240,7 +240,7 @@ std::vector MeshModule::GetMeshModulesWithUIFrames() for (auto i = modules->begin(); i != modules->end(); ++i) { auto &pi = **i; if (pi.wantUIFrame()) { - LOG_DEBUG("Module wants a UI Frame\n"); + LOG_DEBUG("%s wants a UI Frame\n", pi.name); modulesWithUIFrames.push_back(&pi); } } @@ -255,7 +255,7 @@ void MeshModule::observeUIEvents(Observer *observer) auto &pi = **i; Observable *observable = pi.getUIFrameObservable(); if (observable != NULL) { - LOG_DEBUG("Module wants a UI Frame\n"); + LOG_DEBUG("%s wants a UI Frame\n", pi.name); observer->observe(observable); } } @@ -296,4 +296,4 @@ bool MeshModule::isRequestingFocus() } else return false; } -#endif \ No newline at end of file +#endif From ad031dd69f3e4808378b73dc432c68e11824c597 Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Sun, 6 Oct 2024 07:28:05 -0500 Subject: [PATCH 72/88] [create-pull-request] automated change (#4971) Co-authored-by: thebentern <9000580+thebentern@users.noreply.github.com> --- protobufs | 2 +- src/mesh/generated/meshtastic/deviceonly.pb.h | 2 +- src/mesh/generated/meshtastic/localonly.pb.h | 2 +- .../generated/meshtastic/module_config.pb.h | 20 ++++++++++--------- 4 files changed, 14 insertions(+), 12 deletions(-) diff --git a/protobufs b/protobufs index b41970669..5df44cf80 160000 --- a/protobufs +++ b/protobufs @@ -1 +1 @@ -Subproject commit b419706693e0120f7b032d0be0121ae758cfd6e4 +Subproject commit 5df44cf804916f94ce914a1cc4f5b3fb9dc5fe05 diff --git a/src/mesh/generated/meshtastic/deviceonly.pb.h b/src/mesh/generated/meshtastic/deviceonly.pb.h index 0fc09daca..d690acf06 100644 --- a/src/mesh/generated/meshtastic/deviceonly.pb.h +++ b/src/mesh/generated/meshtastic/deviceonly.pb.h @@ -359,7 +359,7 @@ extern const pb_msgdesc_t meshtastic_OEMStore_msg; #define MESHTASTIC_MESHTASTIC_DEVICEONLY_PB_H_MAX_SIZE meshtastic_OEMStore_size #define meshtastic_ChannelFile_size 718 #define meshtastic_NodeInfoLite_size 183 -#define meshtastic_OEMStore_size 3576 +#define meshtastic_OEMStore_size 3578 #define meshtastic_PositionLite_size 28 #define meshtastic_UserLite_size 96 diff --git a/src/mesh/generated/meshtastic/localonly.pb.h b/src/mesh/generated/meshtastic/localonly.pb.h index bac67942c..931de10f5 100644 --- a/src/mesh/generated/meshtastic/localonly.pb.h +++ b/src/mesh/generated/meshtastic/localonly.pb.h @@ -188,7 +188,7 @@ extern const pb_msgdesc_t meshtastic_LocalModuleConfig_msg; /* Maximum encoded size of messages (where known) */ #define MESHTASTIC_MESHTASTIC_LOCALONLY_PB_H_MAX_SIZE meshtastic_LocalConfig_size #define meshtastic_LocalConfig_size 735 -#define meshtastic_LocalModuleConfig_size 695 +#define meshtastic_LocalModuleConfig_size 697 #ifdef __cplusplus } /* extern "C" */ diff --git a/src/mesh/generated/meshtastic/module_config.pb.h b/src/mesh/generated/meshtastic/module_config.pb.h index ce8b8891a..e9be480ce 100644 --- a/src/mesh/generated/meshtastic/module_config.pb.h +++ b/src/mesh/generated/meshtastic/module_config.pb.h @@ -327,14 +327,12 @@ typedef struct _meshtastic_ModuleConfig_TelemetryConfig { /* Interval in seconds of how often we should try to send our air quality metrics to the mesh */ uint32_t air_quality_interval; - /* Interval in seconds of how often we should try to send our - air quality metrics to the mesh */ + /* Enable/disable Power metrics */ bool power_measurement_enabled; /* Interval in seconds of how often we should try to send our - air quality metrics to the mesh */ + power metrics to the mesh */ uint32_t power_update_interval; - /* Interval in seconds of how often we should try to send our - air quality metrics to the mesh */ + /* Enable/Disable the power measurement module on-device display */ bool power_screen_enabled; /* Preferences for the (Health) Telemetry Module Enable/Disable the telemetry measurement module measurement collection */ @@ -342,6 +340,8 @@ typedef struct _meshtastic_ModuleConfig_TelemetryConfig { /* Interval in seconds of how often we should try to send our health metrics to the mesh */ uint32_t health_update_interval; + /* Enable/Disable the health telemetry module on-device display */ + bool health_screen_enabled; } meshtastic_ModuleConfig_TelemetryConfig; /* TODO: REPLACE */ @@ -509,7 +509,7 @@ extern "C" { #define meshtastic_ModuleConfig_ExternalNotificationConfig_init_default {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} #define meshtastic_ModuleConfig_StoreForwardConfig_init_default {0, 0, 0, 0, 0, 0} #define meshtastic_ModuleConfig_RangeTestConfig_init_default {0, 0, 0} -#define meshtastic_ModuleConfig_TelemetryConfig_init_default {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} +#define meshtastic_ModuleConfig_TelemetryConfig_init_default {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} #define meshtastic_ModuleConfig_CannedMessageConfig_init_default {0, 0, 0, 0, _meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_MIN, _meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_MIN, _meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_MIN, 0, 0, "", 0} #define meshtastic_ModuleConfig_AmbientLightingConfig_init_default {0, 0, 0, 0, 0} #define meshtastic_RemoteHardwarePin_init_default {0, "", _meshtastic_RemoteHardwarePinType_MIN} @@ -525,7 +525,7 @@ extern "C" { #define meshtastic_ModuleConfig_ExternalNotificationConfig_init_zero {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} #define meshtastic_ModuleConfig_StoreForwardConfig_init_zero {0, 0, 0, 0, 0, 0} #define meshtastic_ModuleConfig_RangeTestConfig_init_zero {0, 0, 0} -#define meshtastic_ModuleConfig_TelemetryConfig_init_zero {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} +#define meshtastic_ModuleConfig_TelemetryConfig_init_zero {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} #define meshtastic_ModuleConfig_CannedMessageConfig_init_zero {0, 0, 0, 0, _meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_MIN, _meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_MIN, _meshtastic_ModuleConfig_CannedMessageConfig_InputEventChar_MIN, 0, 0, "", 0} #define meshtastic_ModuleConfig_AmbientLightingConfig_init_zero {0, 0, 0, 0, 0} #define meshtastic_RemoteHardwarePin_init_zero {0, "", _meshtastic_RemoteHardwarePinType_MIN} @@ -609,6 +609,7 @@ extern "C" { #define meshtastic_ModuleConfig_TelemetryConfig_power_screen_enabled_tag 10 #define meshtastic_ModuleConfig_TelemetryConfig_health_measurement_enabled_tag 11 #define meshtastic_ModuleConfig_TelemetryConfig_health_update_interval_tag 12 +#define meshtastic_ModuleConfig_TelemetryConfig_health_screen_enabled_tag 13 #define meshtastic_ModuleConfig_CannedMessageConfig_rotary1_enabled_tag 1 #define meshtastic_ModuleConfig_CannedMessageConfig_inputbroker_pin_a_tag 2 #define meshtastic_ModuleConfig_CannedMessageConfig_inputbroker_pin_b_tag 3 @@ -803,7 +804,8 @@ X(a, STATIC, SINGULAR, BOOL, power_measurement_enabled, 8) \ X(a, STATIC, SINGULAR, UINT32, power_update_interval, 9) \ X(a, STATIC, SINGULAR, BOOL, power_screen_enabled, 10) \ X(a, STATIC, SINGULAR, BOOL, health_measurement_enabled, 11) \ -X(a, STATIC, SINGULAR, UINT32, health_update_interval, 12) +X(a, STATIC, SINGULAR, UINT32, health_update_interval, 12) \ +X(a, STATIC, SINGULAR, BOOL, health_screen_enabled, 13) #define meshtastic_ModuleConfig_TelemetryConfig_CALLBACK NULL #define meshtastic_ModuleConfig_TelemetryConfig_DEFAULT NULL @@ -888,7 +890,7 @@ extern const pb_msgdesc_t meshtastic_RemoteHardwarePin_msg; #define meshtastic_ModuleConfig_RemoteHardwareConfig_size 96 #define meshtastic_ModuleConfig_SerialConfig_size 28 #define meshtastic_ModuleConfig_StoreForwardConfig_size 24 -#define meshtastic_ModuleConfig_TelemetryConfig_size 44 +#define meshtastic_ModuleConfig_TelemetryConfig_size 46 #define meshtastic_ModuleConfig_size 257 #define meshtastic_RemoteHardwarePin_size 21 From 7febb41727a0c9ea763d7b4ec3ffebf3e539fd0a Mon Sep 17 00:00:00 2001 From: Tom Fifield Date: Sun, 6 Oct 2024 20:37:20 +0800 Subject: [PATCH 73/88] Trunk format Screen.cpp (#4970) --- src/graphics/Screen.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/graphics/Screen.cpp b/src/graphics/Screen.cpp index 66900c53d..ad42fa979 100644 --- a/src/graphics/Screen.cpp +++ b/src/graphics/Screen.cpp @@ -2485,7 +2485,7 @@ void DebugInfo::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16 #endif } else { #if (defined(USE_EINK) || defined(ILI9341_DRIVER) || defined(ILI9342_DRIVER) || defined(ST7701_CS) || defined(ST7735_CS) || \ - defined(ST7789_CS) || defined(USE_ST7789) || defined(HX8357_CS)) && \ + defined(ST7789_CS) || defined(USE_ST7789) || defined(HX8357_CS)) && \ !defined(DISPLAY_FORCE_SMALL_FONTS) display->drawFastImage(x + SCREEN_WIDTH - 18 - display->getStringWidth(ourId), y + 3 + FONT_HEIGHT_SMALL, 16, 8, imgSFL1); @@ -2817,4 +2817,4 @@ int Screen::handleAdminMessage(const meshtastic_AdminMessage *arg) } // namespace graphics #else graphics::Screen::Screen(ScanI2C::DeviceAddress, meshtastic_Config_DisplayConfig_OledType, OLEDDISPLAY_GEOMETRY) {} -#endif // HAS_SCREEN +#endif // HAS_SCREEN \ No newline at end of file From 001a845ac314f7b3e6de4f7d25584d55373e47c6 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Sun, 6 Oct 2024 07:55:02 -0500 Subject: [PATCH 74/88] Upgrade nanopb (#4973) --- .github/workflows/update_protobufs.yml | 6 +++--- .trunk/trunk.yaml | 4 ++-- bin/regen-protos.bat | 2 +- bin/regen-protos.sh | 6 +++--- 4 files changed, 9 insertions(+), 9 deletions(-) diff --git a/.github/workflows/update_protobufs.yml b/.github/workflows/update_protobufs.yml index 7ce767370..f1c92b860 100644 --- a/.github/workflows/update_protobufs.yml +++ b/.github/workflows/update_protobufs.yml @@ -17,9 +17,9 @@ jobs: - name: Download nanopb run: | - wget https://jpa.kapsi.fi/nanopb/download/nanopb-0.4.8-linux-x86.tar.gz - tar xvzf nanopb-0.4.8-linux-x86.tar.gz - mv nanopb-0.4.8-linux-x86 nanopb-0.4.8 + wget https://jpa.kapsi.fi/nanopb/download/nanopb-0.4.9-linux-x86.tar.gz + tar xvzf nanopb-0.4.9-linux-x86.tar.gz + mv nanopb-0.4.9-linux-x86 nanopb-0.4.9 - name: Re-generate protocol buffers run: | diff --git a/.trunk/trunk.yaml b/.trunk/trunk.yaml index 9ed720c3f..ea4045a16 100644 --- a/.trunk/trunk.yaml +++ b/.trunk/trunk.yaml @@ -11,7 +11,7 @@ lint: - trufflehog@3.82.6 - yamllint@1.35.1 - bandit@1.7.10 - - checkov@3.2.255 + - checkov@3.2.256 - terrascan@1.19.1 - trivy@0.55.2 #- trufflehog@3.63.2-rc0 @@ -28,7 +28,7 @@ lint: - shellcheck@0.10.0 - black@24.8.0 - git-diff-check - - gitleaks@8.19.3 + - gitleaks@8.20.0 - clang-format@16.0.3 - prettier@3.3.3 ignore: diff --git a/bin/regen-protos.bat b/bin/regen-protos.bat index f28ef0025..7fa8f333d 100644 --- a/bin/regen-protos.bat +++ b/bin/regen-protos.bat @@ -1 +1 @@ -cd protobufs && ..\nanopb-0.4.8\generator-bin\protoc.exe --experimental_allow_proto3_optional "--nanopb_out=-S.cpp -v:..\src\mesh\generated" -I=..\protobufs\ ..\protobufs\meshtastic\*.proto +cd protobufs && ..\nanopb-0.4.9\generator-bin\protoc.exe --experimental_allow_proto3_optional "--nanopb_out=-S.cpp -v:..\src\mesh\generated" -I=..\protobufs\ ..\protobufs\meshtastic\*.proto diff --git a/bin/regen-protos.sh b/bin/regen-protos.sh index 2e60784e3..12546bfdc 100755 --- a/bin/regen-protos.sh +++ b/bin/regen-protos.sh @@ -2,10 +2,10 @@ set -e -echo "This script requires https://jpa.kapsi.fi/nanopb/download/ version 0.4.8 to be located in the" +echo "This script requires https://jpa.kapsi.fi/nanopb/download/ version 0.4.9 to be located in the" echo "firmware root directory if the following step fails, you should download the correct" -echo "prebuilt binaries for your computer into nanopb-0.4.8" +echo "prebuilt binaries for your computer into nanopb-0.4.9" # the nanopb tool seems to require that the .options file be in the current directory! cd protobufs -../nanopb-0.4.8/generator-bin/protoc --experimental_allow_proto3_optional "--nanopb_out=-S.cpp -v:../src/mesh/generated/" -I=../protobufs meshtastic/*.proto +../nanopb-0.4.9/generator-bin/protoc --experimental_allow_proto3_optional "--nanopb_out=-S.cpp -v:../src/mesh/generated/" -I=../protobufs meshtastic/*.proto From bb9f003c24e981373cef430011e1538f18594d6d Mon Sep 17 00:00:00 2001 From: Tom Fifield Date: Sun, 6 Oct 2024 20:55:21 +0800 Subject: [PATCH 75/88] Switch EnvironmentTelemetry to use UnitConversions (#4972) We already have a central class for unit conversions, switch EnvironmentTelemetry to that in preparation for HealthTelemetry. --- src/modules/Telemetry/EnvironmentTelemetry.cpp | 11 ++++------- src/modules/Telemetry/EnvironmentTelemetry.h | 1 - 2 files changed, 4 insertions(+), 8 deletions(-) diff --git a/src/modules/Telemetry/EnvironmentTelemetry.cpp b/src/modules/Telemetry/EnvironmentTelemetry.cpp index 147f4ed34..1ccdedeb7 100644 --- a/src/modules/Telemetry/EnvironmentTelemetry.cpp +++ b/src/modules/Telemetry/EnvironmentTelemetry.cpp @@ -10,6 +10,7 @@ #include "PowerFSM.h" #include "RTC.h" #include "Router.h" +#include "UnitConversions.h" #include "main.h" #include "power.h" #include "sleep.h" @@ -182,11 +183,6 @@ bool EnvironmentTelemetryModule::wantUIFrame() return moduleConfig.telemetry.environment_screen_enabled; } -float EnvironmentTelemetryModule::CelsiusToFahrenheit(float c) -{ - return (c * 9) / 5 + 32; -} - void EnvironmentTelemetryModule::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y) { display->setTextAlignment(TEXT_ALIGN_LEFT); @@ -216,7 +212,8 @@ void EnvironmentTelemetryModule::drawFrame(OLEDDisplay *display, OLEDDisplayUiSt String last_temp = String(lastMeasurement.variant.environment_metrics.temperature, 0) + "°C"; if (moduleConfig.telemetry.environment_display_fahrenheit) { - last_temp = String(CelsiusToFahrenheit(lastMeasurement.variant.environment_metrics.temperature), 0) + "°F"; + last_temp = + String(UnitConversions::CelsiusToFahrenheit(lastMeasurement.variant.environment_metrics.temperature), 0) + "°F"; } // Continue with the remaining details @@ -589,4 +586,4 @@ AdminMessageHandleResult EnvironmentTelemetryModule::handleAdminMessageForModule return result; } -#endif +#endif \ No newline at end of file diff --git a/src/modules/Telemetry/EnvironmentTelemetry.h b/src/modules/Telemetry/EnvironmentTelemetry.h index 59d272e78..e680d8bbd 100644 --- a/src/modules/Telemetry/EnvironmentTelemetry.h +++ b/src/modules/Telemetry/EnvironmentTelemetry.h @@ -52,7 +52,6 @@ class EnvironmentTelemetryModule : private concurrency::OSThread, public Protobu meshtastic_AdminMessage *response) override; private: - float CelsiusToFahrenheit(float c); bool firstTime = 1; meshtastic_MeshPacket *lastMeasurementPacket; uint32_t sendToPhoneIntervalMs = SECONDS_IN_MINUTE * 1000; // Send to phone every minute From 830281803f80954023ec5f5ac67228736e6b50bf Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Sun, 6 Oct 2024 08:14:03 -0500 Subject: [PATCH 76/88] [create-pull-request] automated change (#4974) Co-authored-by: thebentern <9000580+thebentern@users.noreply.github.com> --- protobufs | 2 +- src/mesh/generated/meshtastic/admin.pb.cpp | 4 +++- src/mesh/generated/meshtastic/admin.pb.h | 2 +- src/mesh/generated/meshtastic/apponly.pb.cpp | 2 +- src/mesh/generated/meshtastic/apponly.pb.h | 2 +- src/mesh/generated/meshtastic/atak.pb.cpp | 4 +++- src/mesh/generated/meshtastic/atak.pb.h | 2 +- .../generated/meshtastic/cannedmessages.pb.cpp | 2 +- src/mesh/generated/meshtastic/cannedmessages.pb.h | 2 +- src/mesh/generated/meshtastic/channel.pb.cpp | 3 ++- src/mesh/generated/meshtastic/channel.pb.h | 2 +- src/mesh/generated/meshtastic/clientonly.pb.cpp | 2 +- src/mesh/generated/meshtastic/clientonly.pb.h | 2 +- src/mesh/generated/meshtastic/config.pb.cpp | 15 ++++++++++++++- src/mesh/generated/meshtastic/config.pb.h | 14 ++++++++++---- .../generated/meshtastic/connection_status.pb.cpp | 2 +- .../generated/meshtastic/connection_status.pb.h | 2 +- src/mesh/generated/meshtastic/deviceonly.pb.cpp | 3 ++- src/mesh/generated/meshtastic/deviceonly.pb.h | 2 +- src/mesh/generated/meshtastic/localonly.pb.cpp | 2 +- src/mesh/generated/meshtastic/localonly.pb.h | 2 +- src/mesh/generated/meshtastic/mesh.pb.cpp | 11 ++++++++++- src/mesh/generated/meshtastic/mesh.pb.h | 2 +- .../generated/meshtastic/module_config.pb.cpp | 8 +++++++- src/mesh/generated/meshtastic/module_config.pb.h | 2 +- src/mesh/generated/meshtastic/mqtt.pb.cpp | 2 +- src/mesh/generated/meshtastic/mqtt.pb.h | 2 +- src/mesh/generated/meshtastic/paxcount.pb.cpp | 2 +- src/mesh/generated/meshtastic/paxcount.pb.h | 2 +- src/mesh/generated/meshtastic/portnums.pb.cpp | 3 ++- src/mesh/generated/meshtastic/portnums.pb.h | 2 +- src/mesh/generated/meshtastic/powermon.pb.cpp | 4 +++- src/mesh/generated/meshtastic/powermon.pb.h | 2 +- .../generated/meshtastic/remote_hardware.pb.cpp | 3 ++- .../generated/meshtastic/remote_hardware.pb.h | 2 +- src/mesh/generated/meshtastic/rtttl.pb.cpp | 2 +- src/mesh/generated/meshtastic/rtttl.pb.h | 2 +- src/mesh/generated/meshtastic/storeforward.pb.cpp | 3 ++- src/mesh/generated/meshtastic/storeforward.pb.h | 2 +- src/mesh/generated/meshtastic/telemetry.pb.cpp | 3 ++- src/mesh/generated/meshtastic/telemetry.pb.h | 2 +- src/mesh/generated/meshtastic/xmodem.pb.cpp | 3 ++- src/mesh/generated/meshtastic/xmodem.pb.h | 2 +- 43 files changed, 93 insertions(+), 46 deletions(-) diff --git a/protobufs b/protobufs index 5df44cf80..c9ae7fd47 160000 --- a/protobufs +++ b/protobufs @@ -1 +1 @@ -Subproject commit 5df44cf804916f94ce914a1cc4f5b3fb9dc5fe05 +Subproject commit c9ae7fd478bffe5f954b30de6cb140821fe9ff52 diff --git a/src/mesh/generated/meshtastic/admin.pb.cpp b/src/mesh/generated/meshtastic/admin.pb.cpp index 339960302..8b3fd3d1b 100644 --- a/src/mesh/generated/meshtastic/admin.pb.cpp +++ b/src/mesh/generated/meshtastic/admin.pb.cpp @@ -1,5 +1,5 @@ /* Automatically generated nanopb constant definitions */ -/* Generated by nanopb-0.4.8 */ +/* Generated by nanopb-0.4.9 */ #include "meshtastic/admin.pb.h" #if PB_PROTO_HEADER_VERSION != 40 @@ -18,3 +18,5 @@ PB_BIND(meshtastic_NodeRemoteHardwarePinsResponse, meshtastic_NodeRemoteHardware + + diff --git a/src/mesh/generated/meshtastic/admin.pb.h b/src/mesh/generated/meshtastic/admin.pb.h index c1ff7ebd4..bf81269b4 100644 --- a/src/mesh/generated/meshtastic/admin.pb.h +++ b/src/mesh/generated/meshtastic/admin.pb.h @@ -1,5 +1,5 @@ /* Automatically generated nanopb header */ -/* Generated by nanopb-0.4.8 */ +/* Generated by nanopb-0.4.9 */ #ifndef PB_MESHTASTIC_MESHTASTIC_ADMIN_PB_H_INCLUDED #define PB_MESHTASTIC_MESHTASTIC_ADMIN_PB_H_INCLUDED diff --git a/src/mesh/generated/meshtastic/apponly.pb.cpp b/src/mesh/generated/meshtastic/apponly.pb.cpp index 44b0ea3cc..64d43b7ee 100644 --- a/src/mesh/generated/meshtastic/apponly.pb.cpp +++ b/src/mesh/generated/meshtastic/apponly.pb.cpp @@ -1,5 +1,5 @@ /* Automatically generated nanopb constant definitions */ -/* Generated by nanopb-0.4.8 */ +/* Generated by nanopb-0.4.9 */ #include "meshtastic/apponly.pb.h" #if PB_PROTO_HEADER_VERSION != 40 diff --git a/src/mesh/generated/meshtastic/apponly.pb.h b/src/mesh/generated/meshtastic/apponly.pb.h index 31211a91b..dc08d9ff3 100644 --- a/src/mesh/generated/meshtastic/apponly.pb.h +++ b/src/mesh/generated/meshtastic/apponly.pb.h @@ -1,5 +1,5 @@ /* Automatically generated nanopb header */ -/* Generated by nanopb-0.4.8 */ +/* Generated by nanopb-0.4.9 */ #ifndef PB_MESHTASTIC_MESHTASTIC_APPONLY_PB_H_INCLUDED #define PB_MESHTASTIC_MESHTASTIC_APPONLY_PB_H_INCLUDED diff --git a/src/mesh/generated/meshtastic/atak.pb.cpp b/src/mesh/generated/meshtastic/atak.pb.cpp index 491336bcf..6dbc69fb4 100644 --- a/src/mesh/generated/meshtastic/atak.pb.cpp +++ b/src/mesh/generated/meshtastic/atak.pb.cpp @@ -1,5 +1,5 @@ /* Automatically generated nanopb constant definitions */ -/* Generated by nanopb-0.4.8 */ +/* Generated by nanopb-0.4.9 */ #include "meshtastic/atak.pb.h" #if PB_PROTO_HEADER_VERSION != 40 @@ -27,3 +27,5 @@ PB_BIND(meshtastic_PLI, meshtastic_PLI, AUTO) + + diff --git a/src/mesh/generated/meshtastic/atak.pb.h b/src/mesh/generated/meshtastic/atak.pb.h index 7d1ef2995..15a86788b 100644 --- a/src/mesh/generated/meshtastic/atak.pb.h +++ b/src/mesh/generated/meshtastic/atak.pb.h @@ -1,5 +1,5 @@ /* Automatically generated nanopb header */ -/* Generated by nanopb-0.4.8 */ +/* Generated by nanopb-0.4.9 */ #ifndef PB_MESHTASTIC_MESHTASTIC_ATAK_PB_H_INCLUDED #define PB_MESHTASTIC_MESHTASTIC_ATAK_PB_H_INCLUDED diff --git a/src/mesh/generated/meshtastic/cannedmessages.pb.cpp b/src/mesh/generated/meshtastic/cannedmessages.pb.cpp index 71e659be2..9f51e9634 100644 --- a/src/mesh/generated/meshtastic/cannedmessages.pb.cpp +++ b/src/mesh/generated/meshtastic/cannedmessages.pb.cpp @@ -1,5 +1,5 @@ /* Automatically generated nanopb constant definitions */ -/* Generated by nanopb-0.4.8 */ +/* Generated by nanopb-0.4.9 */ #include "meshtastic/cannedmessages.pb.h" #if PB_PROTO_HEADER_VERSION != 40 diff --git a/src/mesh/generated/meshtastic/cannedmessages.pb.h b/src/mesh/generated/meshtastic/cannedmessages.pb.h index c3f9a8b9b..06d14b98f 100644 --- a/src/mesh/generated/meshtastic/cannedmessages.pb.h +++ b/src/mesh/generated/meshtastic/cannedmessages.pb.h @@ -1,5 +1,5 @@ /* Automatically generated nanopb header */ -/* Generated by nanopb-0.4.8 */ +/* Generated by nanopb-0.4.9 */ #ifndef PB_MESHTASTIC_MESHTASTIC_CANNEDMESSAGES_PB_H_INCLUDED #define PB_MESHTASTIC_MESHTASTIC_CANNEDMESSAGES_PB_H_INCLUDED diff --git a/src/mesh/generated/meshtastic/channel.pb.cpp b/src/mesh/generated/meshtastic/channel.pb.cpp index fe76d8140..52f923b13 100644 --- a/src/mesh/generated/meshtastic/channel.pb.cpp +++ b/src/mesh/generated/meshtastic/channel.pb.cpp @@ -1,5 +1,5 @@ /* Automatically generated nanopb constant definitions */ -/* Generated by nanopb-0.4.8 */ +/* Generated by nanopb-0.4.9 */ #include "meshtastic/channel.pb.h" #if PB_PROTO_HEADER_VERSION != 40 @@ -17,3 +17,4 @@ PB_BIND(meshtastic_Channel, meshtastic_Channel, AUTO) + diff --git a/src/mesh/generated/meshtastic/channel.pb.h b/src/mesh/generated/meshtastic/channel.pb.h index d9c7d4ffa..3d617ae39 100644 --- a/src/mesh/generated/meshtastic/channel.pb.h +++ b/src/mesh/generated/meshtastic/channel.pb.h @@ -1,5 +1,5 @@ /* Automatically generated nanopb header */ -/* Generated by nanopb-0.4.8 */ +/* Generated by nanopb-0.4.9 */ #ifndef PB_MESHTASTIC_MESHTASTIC_CHANNEL_PB_H_INCLUDED #define PB_MESHTASTIC_MESHTASTIC_CHANNEL_PB_H_INCLUDED diff --git a/src/mesh/generated/meshtastic/clientonly.pb.cpp b/src/mesh/generated/meshtastic/clientonly.pb.cpp index 44c6f95ce..d99af8cf5 100644 --- a/src/mesh/generated/meshtastic/clientonly.pb.cpp +++ b/src/mesh/generated/meshtastic/clientonly.pb.cpp @@ -1,5 +1,5 @@ /* Automatically generated nanopb constant definitions */ -/* Generated by nanopb-0.4.8 */ +/* Generated by nanopb-0.4.9 */ #include "meshtastic/clientonly.pb.h" #if PB_PROTO_HEADER_VERSION != 40 diff --git a/src/mesh/generated/meshtastic/clientonly.pb.h b/src/mesh/generated/meshtastic/clientonly.pb.h index 5720c1c02..bf32d7875 100644 --- a/src/mesh/generated/meshtastic/clientonly.pb.h +++ b/src/mesh/generated/meshtastic/clientonly.pb.h @@ -1,5 +1,5 @@ /* Automatically generated nanopb header */ -/* Generated by nanopb-0.4.8 */ +/* Generated by nanopb-0.4.9 */ #ifndef PB_MESHTASTIC_MESHTASTIC_CLIENTONLY_PB_H_INCLUDED #define PB_MESHTASTIC_MESHTASTIC_CLIENTONLY_PB_H_INCLUDED diff --git a/src/mesh/generated/meshtastic/config.pb.cpp b/src/mesh/generated/meshtastic/config.pb.cpp index 92c3313bd..23f4d542b 100644 --- a/src/mesh/generated/meshtastic/config.pb.cpp +++ b/src/mesh/generated/meshtastic/config.pb.cpp @@ -1,5 +1,5 @@ /* Automatically generated nanopb constant definitions */ -/* Generated by nanopb-0.4.8 */ +/* Generated by nanopb-0.4.9 */ #include "meshtastic/config.pb.h" #if PB_PROTO_HEADER_VERSION != 40 @@ -46,6 +46,19 @@ PB_BIND(meshtastic_Config_SessionkeyConfig, meshtastic_Config_SessionkeyConfig, + + + + + + + + + + + + + diff --git a/src/mesh/generated/meshtastic/config.pb.h b/src/mesh/generated/meshtastic/config.pb.h index da2e43972..988f852ff 100644 --- a/src/mesh/generated/meshtastic/config.pb.h +++ b/src/mesh/generated/meshtastic/config.pb.h @@ -1,5 +1,5 @@ /* Automatically generated nanopb header */ -/* Generated by nanopb-0.4.8 */ +/* Generated by nanopb-0.4.9 */ #ifndef PB_MESHTASTIC_MESHTASTIC_CONFIG_PB_H_INCLUDED #define PB_MESHTASTIC_MESHTASTIC_CONFIG_PB_H_INCLUDED @@ -238,7 +238,13 @@ typedef enum _meshtastic_Config_LoRaConfig_RegionCode { /* Malaysia 919mhz */ meshtastic_Config_LoRaConfig_RegionCode_MY_919 = 17, /* Singapore 923mhz */ - meshtastic_Config_LoRaConfig_RegionCode_SG_923 = 18 + meshtastic_Config_LoRaConfig_RegionCode_SG_923 = 18, + /* Philippines 433mhz */ + meshtastic_Config_LoRaConfig_RegionCode_PH_433 = 19, + /* Philippines 868mhz */ + meshtastic_Config_LoRaConfig_RegionCode_PH_868 = 20, + /* Philippines 915mhz */ + meshtastic_Config_LoRaConfig_RegionCode_PH_915 = 21 } meshtastic_Config_LoRaConfig_RegionCode; /* Standard predefined channel settings @@ -615,8 +621,8 @@ extern "C" { #define _meshtastic_Config_DisplayConfig_CompassOrientation_ARRAYSIZE ((meshtastic_Config_DisplayConfig_CompassOrientation)(meshtastic_Config_DisplayConfig_CompassOrientation_DEGREES_270_INVERTED+1)) #define _meshtastic_Config_LoRaConfig_RegionCode_MIN meshtastic_Config_LoRaConfig_RegionCode_UNSET -#define _meshtastic_Config_LoRaConfig_RegionCode_MAX meshtastic_Config_LoRaConfig_RegionCode_SG_923 -#define _meshtastic_Config_LoRaConfig_RegionCode_ARRAYSIZE ((meshtastic_Config_LoRaConfig_RegionCode)(meshtastic_Config_LoRaConfig_RegionCode_SG_923+1)) +#define _meshtastic_Config_LoRaConfig_RegionCode_MAX meshtastic_Config_LoRaConfig_RegionCode_PH_915 +#define _meshtastic_Config_LoRaConfig_RegionCode_ARRAYSIZE ((meshtastic_Config_LoRaConfig_RegionCode)(meshtastic_Config_LoRaConfig_RegionCode_PH_915+1)) #define _meshtastic_Config_LoRaConfig_ModemPreset_MIN meshtastic_Config_LoRaConfig_ModemPreset_LONG_FAST #define _meshtastic_Config_LoRaConfig_ModemPreset_MAX meshtastic_Config_LoRaConfig_ModemPreset_SHORT_TURBO diff --git a/src/mesh/generated/meshtastic/connection_status.pb.cpp b/src/mesh/generated/meshtastic/connection_status.pb.cpp index fc5a364dd..d1495bb83 100644 --- a/src/mesh/generated/meshtastic/connection_status.pb.cpp +++ b/src/mesh/generated/meshtastic/connection_status.pb.cpp @@ -1,5 +1,5 @@ /* Automatically generated nanopb constant definitions */ -/* Generated by nanopb-0.4.8 */ +/* Generated by nanopb-0.4.9 */ #include "meshtastic/connection_status.pb.h" #if PB_PROTO_HEADER_VERSION != 40 diff --git a/src/mesh/generated/meshtastic/connection_status.pb.h b/src/mesh/generated/meshtastic/connection_status.pb.h index 1c618e4d4..c433e370b 100644 --- a/src/mesh/generated/meshtastic/connection_status.pb.h +++ b/src/mesh/generated/meshtastic/connection_status.pb.h @@ -1,5 +1,5 @@ /* Automatically generated nanopb header */ -/* Generated by nanopb-0.4.8 */ +/* Generated by nanopb-0.4.9 */ #ifndef PB_MESHTASTIC_MESHTASTIC_CONNECTION_STATUS_PB_H_INCLUDED #define PB_MESHTASTIC_MESHTASTIC_CONNECTION_STATUS_PB_H_INCLUDED diff --git a/src/mesh/generated/meshtastic/deviceonly.pb.cpp b/src/mesh/generated/meshtastic/deviceonly.pb.cpp index 2747ac9d9..135634762 100644 --- a/src/mesh/generated/meshtastic/deviceonly.pb.cpp +++ b/src/mesh/generated/meshtastic/deviceonly.pb.cpp @@ -1,5 +1,5 @@ /* Automatically generated nanopb constant definitions */ -/* Generated by nanopb-0.4.8 */ +/* Generated by nanopb-0.4.9 */ #include "meshtastic/deviceonly.pb.h" #if PB_PROTO_HEADER_VERSION != 40 @@ -26,3 +26,4 @@ PB_BIND(meshtastic_OEMStore, meshtastic_OEMStore, 2) + diff --git a/src/mesh/generated/meshtastic/deviceonly.pb.h b/src/mesh/generated/meshtastic/deviceonly.pb.h index d690acf06..2aa8fda8e 100644 --- a/src/mesh/generated/meshtastic/deviceonly.pb.h +++ b/src/mesh/generated/meshtastic/deviceonly.pb.h @@ -1,5 +1,5 @@ /* Automatically generated nanopb header */ -/* Generated by nanopb-0.4.8 */ +/* Generated by nanopb-0.4.9 */ #ifndef PB_MESHTASTIC_MESHTASTIC_DEVICEONLY_PB_H_INCLUDED #define PB_MESHTASTIC_MESHTASTIC_DEVICEONLY_PB_H_INCLUDED diff --git a/src/mesh/generated/meshtastic/localonly.pb.cpp b/src/mesh/generated/meshtastic/localonly.pb.cpp index 9bc98fb85..0a752a5a8 100644 --- a/src/mesh/generated/meshtastic/localonly.pb.cpp +++ b/src/mesh/generated/meshtastic/localonly.pb.cpp @@ -1,5 +1,5 @@ /* Automatically generated nanopb constant definitions */ -/* Generated by nanopb-0.4.8 */ +/* Generated by nanopb-0.4.9 */ #include "meshtastic/localonly.pb.h" #if PB_PROTO_HEADER_VERSION != 40 diff --git a/src/mesh/generated/meshtastic/localonly.pb.h b/src/mesh/generated/meshtastic/localonly.pb.h index 931de10f5..6409aef74 100644 --- a/src/mesh/generated/meshtastic/localonly.pb.h +++ b/src/mesh/generated/meshtastic/localonly.pb.h @@ -1,5 +1,5 @@ /* Automatically generated nanopb header */ -/* Generated by nanopb-0.4.8 */ +/* Generated by nanopb-0.4.9 */ #ifndef PB_MESHTASTIC_MESHTASTIC_LOCALONLY_PB_H_INCLUDED #define PB_MESHTASTIC_MESHTASTIC_LOCALONLY_PB_H_INCLUDED diff --git a/src/mesh/generated/meshtastic/mesh.pb.cpp b/src/mesh/generated/meshtastic/mesh.pb.cpp index 8c8b9ded7..a0c1e2e73 100644 --- a/src/mesh/generated/meshtastic/mesh.pb.cpp +++ b/src/mesh/generated/meshtastic/mesh.pb.cpp @@ -1,5 +1,5 @@ /* Automatically generated nanopb constant definitions */ -/* Generated by nanopb-0.4.8 */ +/* Generated by nanopb-0.4.9 */ #include "meshtastic/mesh.pb.h" #if PB_PROTO_HEADER_VERSION != 40 @@ -90,4 +90,13 @@ PB_BIND(meshtastic_ChunkedPayloadResponse, meshtastic_ChunkedPayloadResponse, AU + + + + + + + + + diff --git a/src/mesh/generated/meshtastic/mesh.pb.h b/src/mesh/generated/meshtastic/mesh.pb.h index c04f4adb9..fb154e9d5 100644 --- a/src/mesh/generated/meshtastic/mesh.pb.h +++ b/src/mesh/generated/meshtastic/mesh.pb.h @@ -1,5 +1,5 @@ /* Automatically generated nanopb header */ -/* Generated by nanopb-0.4.8 */ +/* Generated by nanopb-0.4.9 */ #ifndef PB_MESHTASTIC_MESHTASTIC_MESH_PB_H_INCLUDED #define PB_MESHTASTIC_MESHTASTIC_MESH_PB_H_INCLUDED diff --git a/src/mesh/generated/meshtastic/module_config.pb.cpp b/src/mesh/generated/meshtastic/module_config.pb.cpp index e1c33e2c1..c40041eab 100644 --- a/src/mesh/generated/meshtastic/module_config.pb.cpp +++ b/src/mesh/generated/meshtastic/module_config.pb.cpp @@ -1,5 +1,5 @@ /* Automatically generated nanopb constant definitions */ -/* Generated by nanopb-0.4.8 */ +/* Generated by nanopb-0.4.9 */ #include "meshtastic/module_config.pb.h" #if PB_PROTO_HEADER_VERSION != 40 @@ -61,3 +61,9 @@ PB_BIND(meshtastic_RemoteHardwarePin, meshtastic_RemoteHardwarePin, AUTO) + + + + + + diff --git a/src/mesh/generated/meshtastic/module_config.pb.h b/src/mesh/generated/meshtastic/module_config.pb.h index e9be480ce..32d5ded23 100644 --- a/src/mesh/generated/meshtastic/module_config.pb.h +++ b/src/mesh/generated/meshtastic/module_config.pb.h @@ -1,5 +1,5 @@ /* Automatically generated nanopb header */ -/* Generated by nanopb-0.4.8 */ +/* Generated by nanopb-0.4.9 */ #ifndef PB_MESHTASTIC_MESHTASTIC_MODULE_CONFIG_PB_H_INCLUDED #define PB_MESHTASTIC_MESHTASTIC_MODULE_CONFIG_PB_H_INCLUDED diff --git a/src/mesh/generated/meshtastic/mqtt.pb.cpp b/src/mesh/generated/meshtastic/mqtt.pb.cpp index f00dd823b..74536cb79 100644 --- a/src/mesh/generated/meshtastic/mqtt.pb.cpp +++ b/src/mesh/generated/meshtastic/mqtt.pb.cpp @@ -1,5 +1,5 @@ /* Automatically generated nanopb constant definitions */ -/* Generated by nanopb-0.4.8 */ +/* Generated by nanopb-0.4.9 */ #include "meshtastic/mqtt.pb.h" #if PB_PROTO_HEADER_VERSION != 40 diff --git a/src/mesh/generated/meshtastic/mqtt.pb.h b/src/mesh/generated/meshtastic/mqtt.pb.h index 8ec9f98c3..4d1027374 100644 --- a/src/mesh/generated/meshtastic/mqtt.pb.h +++ b/src/mesh/generated/meshtastic/mqtt.pb.h @@ -1,5 +1,5 @@ /* Automatically generated nanopb header */ -/* Generated by nanopb-0.4.8 */ +/* Generated by nanopb-0.4.9 */ #ifndef PB_MESHTASTIC_MESHTASTIC_MQTT_PB_H_INCLUDED #define PB_MESHTASTIC_MESHTASTIC_MQTT_PB_H_INCLUDED diff --git a/src/mesh/generated/meshtastic/paxcount.pb.cpp b/src/mesh/generated/meshtastic/paxcount.pb.cpp index 67f07a31b..403288147 100644 --- a/src/mesh/generated/meshtastic/paxcount.pb.cpp +++ b/src/mesh/generated/meshtastic/paxcount.pb.cpp @@ -1,5 +1,5 @@ /* Automatically generated nanopb constant definitions */ -/* Generated by nanopb-0.4.8 */ +/* Generated by nanopb-0.4.9 */ #include "meshtastic/paxcount.pb.h" #if PB_PROTO_HEADER_VERSION != 40 diff --git a/src/mesh/generated/meshtastic/paxcount.pb.h b/src/mesh/generated/meshtastic/paxcount.pb.h index 09377d833..b6b51fdd5 100644 --- a/src/mesh/generated/meshtastic/paxcount.pb.h +++ b/src/mesh/generated/meshtastic/paxcount.pb.h @@ -1,5 +1,5 @@ /* Automatically generated nanopb header */ -/* Generated by nanopb-0.4.8 */ +/* Generated by nanopb-0.4.9 */ #ifndef PB_MESHTASTIC_MESHTASTIC_PAXCOUNT_PB_H_INCLUDED #define PB_MESHTASTIC_MESHTASTIC_PAXCOUNT_PB_H_INCLUDED diff --git a/src/mesh/generated/meshtastic/portnums.pb.cpp b/src/mesh/generated/meshtastic/portnums.pb.cpp index 8f32c0851..8fca9af79 100644 --- a/src/mesh/generated/meshtastic/portnums.pb.cpp +++ b/src/mesh/generated/meshtastic/portnums.pb.cpp @@ -1,5 +1,5 @@ /* Automatically generated nanopb constant definitions */ -/* Generated by nanopb-0.4.8 */ +/* Generated by nanopb-0.4.9 */ #include "meshtastic/portnums.pb.h" #if PB_PROTO_HEADER_VERSION != 40 @@ -8,3 +8,4 @@ + diff --git a/src/mesh/generated/meshtastic/portnums.pb.h b/src/mesh/generated/meshtastic/portnums.pb.h index b9e537ddf..df6cf32c2 100644 --- a/src/mesh/generated/meshtastic/portnums.pb.h +++ b/src/mesh/generated/meshtastic/portnums.pb.h @@ -1,5 +1,5 @@ /* Automatically generated nanopb header */ -/* Generated by nanopb-0.4.8 */ +/* Generated by nanopb-0.4.9 */ #ifndef PB_MESHTASTIC_MESHTASTIC_PORTNUMS_PB_H_INCLUDED #define PB_MESHTASTIC_MESHTASTIC_PORTNUMS_PB_H_INCLUDED diff --git a/src/mesh/generated/meshtastic/powermon.pb.cpp b/src/mesh/generated/meshtastic/powermon.pb.cpp index ce41ea021..6a9b7551a 100644 --- a/src/mesh/generated/meshtastic/powermon.pb.cpp +++ b/src/mesh/generated/meshtastic/powermon.pb.cpp @@ -1,5 +1,5 @@ /* Automatically generated nanopb constant definitions */ -/* Generated by nanopb-0.4.8 */ +/* Generated by nanopb-0.4.9 */ #include "meshtastic/powermon.pb.h" #if PB_PROTO_HEADER_VERSION != 40 @@ -15,3 +15,5 @@ PB_BIND(meshtastic_PowerStressMessage, meshtastic_PowerStressMessage, AUTO) + + diff --git a/src/mesh/generated/meshtastic/powermon.pb.h b/src/mesh/generated/meshtastic/powermon.pb.h index 7de0618e9..5add85b85 100644 --- a/src/mesh/generated/meshtastic/powermon.pb.h +++ b/src/mesh/generated/meshtastic/powermon.pb.h @@ -1,5 +1,5 @@ /* Automatically generated nanopb header */ -/* Generated by nanopb-0.4.8 */ +/* Generated by nanopb-0.4.9 */ #ifndef PB_MESHTASTIC_MESHTASTIC_POWERMON_PB_H_INCLUDED #define PB_MESHTASTIC_MESHTASTIC_POWERMON_PB_H_INCLUDED diff --git a/src/mesh/generated/meshtastic/remote_hardware.pb.cpp b/src/mesh/generated/meshtastic/remote_hardware.pb.cpp index 4a23698b2..239950e7e 100644 --- a/src/mesh/generated/meshtastic/remote_hardware.pb.cpp +++ b/src/mesh/generated/meshtastic/remote_hardware.pb.cpp @@ -1,5 +1,5 @@ /* Automatically generated nanopb constant definitions */ -/* Generated by nanopb-0.4.8 */ +/* Generated by nanopb-0.4.9 */ #include "meshtastic/remote_hardware.pb.h" #if PB_PROTO_HEADER_VERSION != 40 @@ -11,3 +11,4 @@ PB_BIND(meshtastic_HardwareMessage, meshtastic_HardwareMessage, AUTO) + diff --git a/src/mesh/generated/meshtastic/remote_hardware.pb.h b/src/mesh/generated/meshtastic/remote_hardware.pb.h index 936034b62..ade250e93 100644 --- a/src/mesh/generated/meshtastic/remote_hardware.pb.h +++ b/src/mesh/generated/meshtastic/remote_hardware.pb.h @@ -1,5 +1,5 @@ /* Automatically generated nanopb header */ -/* Generated by nanopb-0.4.8 */ +/* Generated by nanopb-0.4.9 */ #ifndef PB_MESHTASTIC_MESHTASTIC_REMOTE_HARDWARE_PB_H_INCLUDED #define PB_MESHTASTIC_MESHTASTIC_REMOTE_HARDWARE_PB_H_INCLUDED diff --git a/src/mesh/generated/meshtastic/rtttl.pb.cpp b/src/mesh/generated/meshtastic/rtttl.pb.cpp index 8367fdbce..61ad8b73f 100644 --- a/src/mesh/generated/meshtastic/rtttl.pb.cpp +++ b/src/mesh/generated/meshtastic/rtttl.pb.cpp @@ -1,5 +1,5 @@ /* Automatically generated nanopb constant definitions */ -/* Generated by nanopb-0.4.8 */ +/* Generated by nanopb-0.4.9 */ #include "meshtastic/rtttl.pb.h" #if PB_PROTO_HEADER_VERSION != 40 diff --git a/src/mesh/generated/meshtastic/rtttl.pb.h b/src/mesh/generated/meshtastic/rtttl.pb.h index 452b0cf4b..2b7e35f11 100644 --- a/src/mesh/generated/meshtastic/rtttl.pb.h +++ b/src/mesh/generated/meshtastic/rtttl.pb.h @@ -1,5 +1,5 @@ /* Automatically generated nanopb header */ -/* Generated by nanopb-0.4.8 */ +/* Generated by nanopb-0.4.9 */ #ifndef PB_MESHTASTIC_MESHTASTIC_RTTTL_PB_H_INCLUDED #define PB_MESHTASTIC_MESHTASTIC_RTTTL_PB_H_INCLUDED diff --git a/src/mesh/generated/meshtastic/storeforward.pb.cpp b/src/mesh/generated/meshtastic/storeforward.pb.cpp index 5b3fadd9a..71a232bf6 100644 --- a/src/mesh/generated/meshtastic/storeforward.pb.cpp +++ b/src/mesh/generated/meshtastic/storeforward.pb.cpp @@ -1,5 +1,5 @@ /* Automatically generated nanopb constant definitions */ -/* Generated by nanopb-0.4.8 */ +/* Generated by nanopb-0.4.9 */ #include "meshtastic/storeforward.pb.h" #if PB_PROTO_HEADER_VERSION != 40 @@ -20,3 +20,4 @@ PB_BIND(meshtastic_StoreAndForward_Heartbeat, meshtastic_StoreAndForward_Heartbe + diff --git a/src/mesh/generated/meshtastic/storeforward.pb.h b/src/mesh/generated/meshtastic/storeforward.pb.h index 311596c7f..71f2fcad5 100644 --- a/src/mesh/generated/meshtastic/storeforward.pb.h +++ b/src/mesh/generated/meshtastic/storeforward.pb.h @@ -1,5 +1,5 @@ /* Automatically generated nanopb header */ -/* Generated by nanopb-0.4.8 */ +/* Generated by nanopb-0.4.9 */ #ifndef PB_MESHTASTIC_MESHTASTIC_STOREFORWARD_PB_H_INCLUDED #define PB_MESHTASTIC_MESHTASTIC_STOREFORWARD_PB_H_INCLUDED diff --git a/src/mesh/generated/meshtastic/telemetry.pb.cpp b/src/mesh/generated/meshtastic/telemetry.pb.cpp index b9c1da7a0..f6d39da6e 100644 --- a/src/mesh/generated/meshtastic/telemetry.pb.cpp +++ b/src/mesh/generated/meshtastic/telemetry.pb.cpp @@ -1,5 +1,5 @@ /* Automatically generated nanopb constant definitions */ -/* Generated by nanopb-0.4.8 */ +/* Generated by nanopb-0.4.9 */ #include "meshtastic/telemetry.pb.h" #if PB_PROTO_HEADER_VERSION != 40 @@ -32,3 +32,4 @@ PB_BIND(meshtastic_Nau7802Config, meshtastic_Nau7802Config, AUTO) + diff --git a/src/mesh/generated/meshtastic/telemetry.pb.h b/src/mesh/generated/meshtastic/telemetry.pb.h index cbe71ed52..a33988129 100644 --- a/src/mesh/generated/meshtastic/telemetry.pb.h +++ b/src/mesh/generated/meshtastic/telemetry.pb.h @@ -1,5 +1,5 @@ /* Automatically generated nanopb header */ -/* Generated by nanopb-0.4.8 */ +/* Generated by nanopb-0.4.9 */ #ifndef PB_MESHTASTIC_MESHTASTIC_TELEMETRY_PB_H_INCLUDED #define PB_MESHTASTIC_MESHTASTIC_TELEMETRY_PB_H_INCLUDED diff --git a/src/mesh/generated/meshtastic/xmodem.pb.cpp b/src/mesh/generated/meshtastic/xmodem.pb.cpp index 8e5cde457..3960ccdaa 100644 --- a/src/mesh/generated/meshtastic/xmodem.pb.cpp +++ b/src/mesh/generated/meshtastic/xmodem.pb.cpp @@ -1,5 +1,5 @@ /* Automatically generated nanopb constant definitions */ -/* Generated by nanopb-0.4.8 */ +/* Generated by nanopb-0.4.9 */ #include "meshtastic/xmodem.pb.h" #if PB_PROTO_HEADER_VERSION != 40 @@ -11,3 +11,4 @@ PB_BIND(meshtastic_XModem, meshtastic_XModem, AUTO) + diff --git a/src/mesh/generated/meshtastic/xmodem.pb.h b/src/mesh/generated/meshtastic/xmodem.pb.h index 67bd0869f..76edc0df6 100644 --- a/src/mesh/generated/meshtastic/xmodem.pb.h +++ b/src/mesh/generated/meshtastic/xmodem.pb.h @@ -1,5 +1,5 @@ /* Automatically generated nanopb header */ -/* Generated by nanopb-0.4.8 */ +/* Generated by nanopb-0.4.9 */ #ifndef PB_MESHTASTIC_MESHTASTIC_XMODEM_PB_H_INCLUDED #define PB_MESHTASTIC_MESHTASTIC_XMODEM_PB_H_INCLUDED From 234a56446b6352490a2e30c5faec0860e8f17e27 Mon Sep 17 00:00:00 2001 From: Tom Fifield Date: Sun, 6 Oct 2024 22:31:13 +0800 Subject: [PATCH 77/88] Add frequencies for Philippines (#4951) There are three different frequencies available for Meshtastic in the Philippines, each with pros and cons: 433 - 434.7 MHz <10 mW erp 868 - 869.4 MHz <25 mW erp 915 - 918 MHz <250 mW EIRP, no external antennna allowed Philippines may also use LORA_24 unrestricted at up to 10mW, or up to 250mW if there is no external antennna. Frequency rules in the Philippines are determined by aggregating the information in laws, following the circulars referenced in the [National Radio Frequency Allocation Table (NRFAT)](https://ntc.gov.ph/wp-content/uploads/2022/frequencyallocations/NRFAT_Rev_2020.pdf) and then circulars that amend the circulars referenced in the NRFAT. A full description of the regulatory basis can be found in the github issue: https://github.com/meshtastic/firmware/issues/4948#issuecomment-2394926135 For 433MHz and 868MHz we refer to the Low Power Equipment rules for "Non-specific Short Range Devices, Telemetry, Telecommand, Alarms, Data In General and Other Similar Applications.". For 915MHz and Wireless Data Network Services indoor device rules. A device approved by the NTC is required for any use of Meshtastic in the Philippines. fixes https://github.com/meshtastic/firmware/issues/4948 Co-authored-by: Ben Meadors --- src/mesh/RadioInterface.cpp | 13 ++++++++++++- 1 file changed, 12 insertions(+), 1 deletion(-) diff --git a/src/mesh/RadioInterface.cpp b/src/mesh/RadioInterface.cpp index b915f94bd..7501852f2 100644 --- a/src/mesh/RadioInterface.cpp +++ b/src/mesh/RadioInterface.cpp @@ -136,6 +136,17 @@ const RegionInfo regions[] = { */ RDEF(SG_923, 917.0f, 925.0f, 100, 0, 20, true, false, false), + /* + Philippines + 433 - 434.7 MHz <10 mW erp, NTC approved device required + 868 - 869.4 MHz <25 mW erp, NTC approved device required + 915 - 918 MHz <250 mW EIRP, no external antennna allowed + https://github.com/meshtastic/firmware/issues/4948#issuecomment-2394926135 + */ + + RDEF(PH_433, 433.0f, 434.7f, 100, 0, 10, true, false, false), RDEF(PH_868, 868.0f, 869.4f, 100, 0, 14, true, false, false), + RDEF(PH_915, 915.0f, 918.0f, 100, 0, 24, true, false, false), + /* 2.4 GHZ WLAN Band equivalent. Only for SX128x chips. */ @@ -614,4 +625,4 @@ size_t RadioInterface::beginSending(meshtastic_MeshPacket *p) sendingPacket = p; return p->encrypted.size + sizeof(PacketHeader); -} \ No newline at end of file +} From 93d874b0138de1c18dceff5825ac3de03a78af24 Mon Sep 17 00:00:00 2001 From: Jonathan Bennett Date: Mon, 7 Oct 2024 05:09:19 -0500 Subject: [PATCH 78/88] set tz config from string if unset (#4979) --- src/main.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/src/main.cpp b/src/main.cpp index 95ac7c1c3..25059f3c7 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -718,6 +718,7 @@ void setup() setenv("TZ", "GMT0", 1); } else { setenv("TZ", (const char *)slipstreamTZString, 1); + strcpy(config.device.tzdef, (const char *)slipstreamTZString); } } tzset(); From 53f189fff4b05b171d6f2500e17d6d14da1e6403 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Mon, 7 Oct 2024 06:43:55 -0500 Subject: [PATCH 79/88] Remove has_rx * on installDefaultDeviceState (#4982) --- src/mesh/NodeDB.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/mesh/NodeDB.cpp b/src/mesh/NodeDB.cpp index 49f0cbc62..639e8109b 100644 --- a/src/mesh/NodeDB.cpp +++ b/src/mesh/NodeDB.cpp @@ -626,6 +626,8 @@ void NodeDB::installDefaultDeviceState() // devicestate.node_db_lite_count = 0; devicestate.version = DEVICESTATE_CUR_VER; devicestate.receive_queue_count = 0; // Not yet implemented FIXME + devicestate.has_rx_waypoint = false; + devicestate.has_rx_text_message = false; generatePacketId(); // FIXME - ugly way to init current_packet_id; From 94ecbad90442428a1ecf8a15b8c3d15a4bade060 Mon Sep 17 00:00:00 2001 From: Mictronics Date: Mon, 7 Oct 2024 19:44:21 +0200 Subject: [PATCH 80/88] Fix storage of admin key when installing default config. (#4995) * Fix LED pinout for T-Echo board marked v1.0, date 2021-6-28 * Merge PR #420 * Fixed double and missing Default class. * Use correct format specifier and fixed typo. * Removed duplicate code. * Fix error: #if with no expression * Fix warning: extra tokens at end of #endif directive. * Fix antenna switching logic. Complementary-pin control logic is required on the rp2040-lora board. * Fix deprecated macros. * Set RP2040 in dormant mode when deep sleep is triggered. * Fix array out of bounds read. * Admin key count needs to be set otherwise the key will be zero loaded after reset. * Don't reset the admin key size when loading defaults. Preserve an existing key in config if possible. --------- Co-authored-by: Ben Meadors --- src/mesh/NodeDB.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/src/mesh/NodeDB.cpp b/src/mesh/NodeDB.cpp index 639e8109b..97ded5a50 100644 --- a/src/mesh/NodeDB.cpp +++ b/src/mesh/NodeDB.cpp @@ -317,8 +317,7 @@ void NodeDB::installDefaultConfig(bool preserveKey = false) #ifdef USERPREFS_USE_ADMIN_KEY memcpy(config.security.admin_key[0].bytes, USERPREFS_ADMIN_KEY, 32); config.security.admin_key[0].size = 32; -#else - config.security.admin_key[0].size = 0; + config.security.admin_key_count = 1; #endif if (shouldPreserveKey) { config.security.private_key.size = 32; From 1c54388bb897ac2a5617fc9a85e1b045265826e3 Mon Sep 17 00:00:00 2001 From: HarukiToreda <116696711+HarukiToreda@users.noreply.github.com> Date: Mon, 7 Oct 2024 16:16:10 -0400 Subject: [PATCH 81/88] Toggle Bluetooth with Fn+b shortcut (#4977) * Toggle Blutooth with Fn+b shortcut Problem: As many are aware, ESP32 devices are known for their high power consumption. For instance, the Heltec ESP32 V3 draws around 110mA when powered on with the screen active and connected to a phone via Bluetooth. The Bluetooth radio alone is responsible for approximately 50mA of that consumption. For keyboard-based standalone devices, which rarely need Bluetooth other than for changing settings, users were forced to keep Bluetooth on regardless of necessity. There was no way to toggle Bluetooth on or off without physically connecting the device to a computer via serial or using the admin channel, which required another node for access. Solution: I implemented a new feature that allows users to turn off Bluetooth on keyboard devices by pressing Fn+b and turn it back on when needed. This enhancement significantly improves power efficiency for these devices. Result: With Bluetooth off, the device now consumes only 55mA. When combined with Power Save mode, the consumption can drop as low as 11mA, a substantial reduction from the previous 110mA. Users can still easily reconnect to a phone using the shortcut when necessary, offering greater flexibility and extended battery life. * Remove 1 reboot at least. I was able to prevent a reboot using the disableBluetooth(); command, current tested at 47-55mA, it doesn't require a reboot to turn off, but it does need reboot to turn back on. * Update CannedMessageModule.cpp --- src/input/InputBroker.h | 1 + src/input/kbI2cBase.cpp | 1 + src/modules/CannedMessageModule.cpp | 17 ++++++++++++++++- 3 files changed, 18 insertions(+), 1 deletion(-) diff --git a/src/input/InputBroker.h b/src/input/InputBroker.h index 17c621c8a..db7524bb0 100644 --- a/src/input/InputBroker.h +++ b/src/input/InputBroker.h @@ -18,6 +18,7 @@ #define INPUT_BROKER_MSG_RIGHT 0xb7 #define INPUT_BROKER_MSG_FN_SYMBOL_ON 0xf1 #define INPUT_BROKER_MSG_FN_SYMBOL_OFF 0xf2 +#define INPUT_BROKER_MSG_BLUETOOTH_TOGGLE 0xAA typedef struct _InputEvent { const char *source; diff --git a/src/input/kbI2cBase.cpp b/src/input/kbI2cBase.cpp index 4fbca76e5..8b201cd22 100644 --- a/src/input/kbI2cBase.cpp +++ b/src/input/kbI2cBase.cpp @@ -297,6 +297,7 @@ int32_t KbI2cBase::runOnce() case 0x9e: // fn+g INPUT_BROKER_MSG_GPS_TOGGLE case 0xaf: // fn+space INPUT_BROKER_MSG_SEND_PING case 0x8b: // fn+del INPUT_BROKEN_MSG_DISMISS_FRAME + case 0xAA: // fn+b INPUT_BROKER_MSG_BLUETOOTH_TOGGLE // just pass those unmodified e.inputEvent = ANYKEY; e.kbchar = c; diff --git a/src/modules/CannedMessageModule.cpp b/src/modules/CannedMessageModule.cpp index 615a1ab54..ed0dce25f 100644 --- a/src/modules/CannedMessageModule.cpp +++ b/src/modules/CannedMessageModule.cpp @@ -12,6 +12,7 @@ #include "detect/ScanI2C.h" #include "input/ScanAndSelect.h" #include "mesh/generated/meshtastic/cannedmessages.pb.h" +#include "modules/AdminModule.h" #include "main.h" // for cardkb_found #include "modules/ExternalNotificationModule.h" // for buzzer control @@ -268,6 +269,21 @@ int CannedMessageModule::handleInputEvent(const InputEvent *event) showTemporaryMessage("GPS Toggled"); #endif break; + case INPUT_BROKER_MSG_BLUETOOTH_TOGGLE: // toggle Bluetooth on/off + if (config.bluetooth.enabled == true) { + config.bluetooth.enabled = false; + LOG_INFO("User toggled Bluetooth"); + nodeDB->saveToDisk(); + disableBluetooth(); + showTemporaryMessage("Bluetooth OFF"); + } else if (config.bluetooth.enabled == false) { + config.bluetooth.enabled = true; + LOG_INFO("User toggled Bluetooth"); + nodeDB->saveToDisk(); + rebootAtMsec = millis() + 2000; + showTemporaryMessage("Bluetooth ON\nReboot"); + } + break; case INPUT_BROKER_MSG_SEND_PING: // fn+space send network ping like double press does service->refreshLocalMeshNode(); if (service->trySendPosition(NODENUM_BROADCAST, true)) { @@ -1145,7 +1161,6 @@ void CannedMessageModule::loadProtoForModule() installDefaultCannedMessageModuleConfig(); } } - /** * @brief Save the module config to file. * From 411aedaf5d52d9d95219df43aa521546fb54cca6 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Mon, 7 Oct 2024 19:50:44 -0500 Subject: [PATCH 82/88] Add health telemetry module (#4927) * Add stub health telemetry module * Add detection for MAX30102 Health Sensor It lives on I2C bus at 0x57, which conflicts with an existing sensor. Add code to check the PARTID register for its response 0x15 per spec. * Add detection for MLX90614 An IR Temperature sensor suitable for livestock monitoring. * Add libraries for MLX90614 and MAX30102 sensors * Fix Trunk * Add support for MLX90614 IR Temperature Sensor * Add support for MAX30102 (Temperature) * Make it build - our first HealthTelemetry on the mesh. If a MAX30102 is connected, its temperature will be sent to the mesh as HealthTelemetry. * Add spo2 and heart rate calculations to MAX30102 * Switch MLX90614 to Adafruit library Sparkfun was having fun with SDA/SCL variables which we can avoid by switching to this highly similar library. * Enable HealthTelemetry if MLX90614 detected * Change MLX90614 emissivity for human skin. * Add health screen! * Remove autogenerated file from branch * Preparing for review * Fix MeshService master sync from before. * Prepare for review * For the americans * Fix native build * Fix for devices with no screen * Remove extra log causing issues --------- Co-authored-by: Tom Fifield --- platformio.ini | 2 + src/configuration.h | 2 + src/detect/ScanI2C.h | 4 +- src/detect/ScanI2CTwoWire.cpp | 14 +- src/main.cpp | 2 + src/mesh/NodeDB.cpp | 2 + src/modules/Modules.cpp | 5 + src/modules/Telemetry/HealthTelemetry.cpp | 249 ++++++++++++++++++ src/modules/Telemetry/HealthTelemetry.h | 60 +++++ .../Telemetry/Sensor/MAX30102Sensor.cpp | 83 ++++++ src/modules/Telemetry/Sensor/MAX30102Sensor.h | 26 ++ .../Telemetry/Sensor/MLX90614Sensor.cpp | 44 ++++ src/modules/Telemetry/Sensor/MLX90614Sensor.h | 24 ++ 13 files changed, 515 insertions(+), 2 deletions(-) create mode 100644 src/modules/Telemetry/HealthTelemetry.cpp create mode 100644 src/modules/Telemetry/HealthTelemetry.h create mode 100644 src/modules/Telemetry/Sensor/MAX30102Sensor.cpp create mode 100644 src/modules/Telemetry/Sensor/MAX30102Sensor.h create mode 100644 src/modules/Telemetry/Sensor/MLX90614Sensor.cpp create mode 100644 src/modules/Telemetry/Sensor/MLX90614Sensor.h diff --git a/platformio.ini b/platformio.ini index 5dcf61afd..2f76c8236 100644 --- a/platformio.ini +++ b/platformio.ini @@ -152,6 +152,8 @@ lib_deps = ClosedCube OPT3001@^1.1.2 emotibit/EmotiBit MLX90632@^1.0.8 dfrobot/DFRobot_RTU@^1.0.3 + sparkfun/SparkFun MAX3010x Pulse and Proximity Sensor Library@^1.1.2 + adafruit/Adafruit MLX90614 Library@^2.1.5 https://github.com/boschsensortec/Bosch-BSEC2-Library#v1.7.2502 boschsensortec/BME68x Sensor Library@^1.1.40407 diff --git a/src/configuration.h b/src/configuration.h index 3cd93ec83..975c9fc68 100644 --- a/src/configuration.h +++ b/src/configuration.h @@ -144,6 +144,8 @@ along with this program. If not, see . #define MLX90632_ADDR 0x3A #define DFROBOT_LARK_ADDR 0x42 #define NAU7802_ADDR 0x2A +#define MAX30102_ADDR 0x57 +#define MLX90614_ADDR 0x5A // ----------------------------------------------------------------------------- // ACCELEROMETER diff --git a/src/detect/ScanI2C.h b/src/detect/ScanI2C.h index 3b49026ce..920af06c7 100644 --- a/src/detect/ScanI2C.h +++ b/src/detect/ScanI2C.h @@ -52,13 +52,15 @@ class ScanI2C TSL2591, OPT3001, MLX90632, + MLX90614, AHT10, BMX160, DFROBOT_LARK, NAU7802, FT6336U, STK8BAXX, - ICM20948 + ICM20948, + MAX30102 } DeviceType; // typedef uint8_t DeviceAddress; diff --git a/src/detect/ScanI2CTwoWire.cpp b/src/detect/ScanI2CTwoWire.cpp index 43340765a..74597fbc3 100644 --- a/src/detect/ScanI2CTwoWire.cpp +++ b/src/detect/ScanI2CTwoWire.cpp @@ -356,7 +356,18 @@ void ScanI2CTwoWire::scanPort(I2CPort port, uint8_t *address, uint8_t asize) break; SCAN_SIMPLE_CASE(SHTC3_ADDR, SHTC3, "SHTC3 sensor found\n") - SCAN_SIMPLE_CASE(RCWL9620_ADDR, RCWL9620, "RCWL9620 sensor found\n") + case RCWL9620_ADDR: + // get MAX30102 PARTID + registerValue = getRegisterValue(ScanI2CTwoWire::RegisterLocation(addr, 0xFF), 1); + if (registerValue == 0x15) { + type = MAX30102; + LOG_INFO("MAX30102 Health sensor found\n"); + break; + } else { + type = RCWL9620; + LOG_INFO("RCWL9620 sensor found\n"); + } + break; case LPS22HB_ADDR_ALT: SCAN_SIMPLE_CASE(LPS22HB_ADDR, LPS22HB, "LPS22HB sensor found\n") @@ -394,6 +405,7 @@ void ScanI2CTwoWire::scanPort(I2CPort port, uint8_t *address, uint8_t asize) SCAN_SIMPLE_CASE(NAU7802_ADDR, NAU7802, "NAU7802 based scale found\n"); SCAN_SIMPLE_CASE(FT6336U_ADDR, FT6336U, "FT6336U touchscreen found\n"); SCAN_SIMPLE_CASE(MAX1704X_ADDR, MAX17048, "MAX17048 lipo fuel gauge found\n"); + SCAN_SIMPLE_CASE(MLX90614_ADDR, MLX90614, "MLX90614 IR temp sensor found\n"); case ICM20948_ADDR: // same as BMX160_ADDR case ICM20948_ADDR_ALT: // same as MPU6050_ADDR diff --git a/src/main.cpp b/src/main.cpp index 25059f3c7..9ddc0864c 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -580,10 +580,12 @@ void setup() SCANNER_TO_SENSORS_MAP(ScanI2C::DeviceType::TSL2591, meshtastic_TelemetrySensorType_TSL25911FN) SCANNER_TO_SENSORS_MAP(ScanI2C::DeviceType::OPT3001, meshtastic_TelemetrySensorType_OPT3001) SCANNER_TO_SENSORS_MAP(ScanI2C::DeviceType::MLX90632, meshtastic_TelemetrySensorType_MLX90632) + SCANNER_TO_SENSORS_MAP(ScanI2C::DeviceType::MLX90614, meshtastic_TelemetrySensorType_MLX90614) SCANNER_TO_SENSORS_MAP(ScanI2C::DeviceType::SHT4X, meshtastic_TelemetrySensorType_SHT4X) SCANNER_TO_SENSORS_MAP(ScanI2C::DeviceType::AHT10, meshtastic_TelemetrySensorType_AHT10) SCANNER_TO_SENSORS_MAP(ScanI2C::DeviceType::DFROBOT_LARK, meshtastic_TelemetrySensorType_DFROBOT_LARK) SCANNER_TO_SENSORS_MAP(ScanI2C::DeviceType::ICM20948, meshtastic_TelemetrySensorType_ICM20948) + SCANNER_TO_SENSORS_MAP(ScanI2C::DeviceType::MAX30102, meshtastic_TelemetrySensorType_MAX30102) i2cScanner.reset(); #endif diff --git a/src/mesh/NodeDB.cpp b/src/mesh/NodeDB.cpp index 97ded5a50..0d9605161 100644 --- a/src/mesh/NodeDB.cpp +++ b/src/mesh/NodeDB.cpp @@ -533,6 +533,7 @@ void NodeDB::installRoleDefaults(meshtastic_Config_DeviceConfig_Role role) moduleConfig.telemetry.device_update_interval = UINT32_MAX; moduleConfig.telemetry.environment_update_interval = UINT32_MAX; moduleConfig.telemetry.air_quality_interval = UINT32_MAX; + moduleConfig.telemetry.health_update_interval = UINT32_MAX; } } @@ -543,6 +544,7 @@ void NodeDB::initModuleConfigIntervals() moduleConfig.telemetry.environment_update_interval = 0; moduleConfig.telemetry.air_quality_interval = 0; moduleConfig.telemetry.power_update_interval = 0; + moduleConfig.telemetry.health_update_interval = 0; moduleConfig.neighbor_info.update_interval = 0; moduleConfig.paxcounter.paxcounter_update_interval = 0; } diff --git a/src/modules/Modules.cpp b/src/modules/Modules.cpp index 554fad6a9..ad3f0ace4 100644 --- a/src/modules/Modules.cpp +++ b/src/modules/Modules.cpp @@ -58,6 +58,7 @@ #include "main.h" #include "modules/Telemetry/AirQualityTelemetry.h" #include "modules/Telemetry/EnvironmentTelemetry.h" +#include "modules/Telemetry/HealthTelemetry.h" #endif #if HAS_TELEMETRY && !MESHTASTIC_EXCLUDE_POWER_TELEMETRY #include "modules/Telemetry/PowerTelemetry.h" @@ -194,6 +195,10 @@ void setupModules() if (nodeTelemetrySensorsMap[meshtastic_TelemetrySensorType_PMSA003I].first > 0) { new AirQualityTelemetryModule(); } + if (nodeTelemetrySensorsMap[meshtastic_TelemetrySensorType_MAX30102].first > 0 || + nodeTelemetrySensorsMap[meshtastic_TelemetrySensorType_MLX90614].first > 0) { + new HealthTelemetryModule(); + } #endif #if HAS_TELEMETRY && !MESHTASTIC_EXCLUDE_POWER_TELEMETRY && !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR new PowerTelemetryModule(); diff --git a/src/modules/Telemetry/HealthTelemetry.cpp b/src/modules/Telemetry/HealthTelemetry.cpp new file mode 100644 index 000000000..bcf9d9d57 --- /dev/null +++ b/src/modules/Telemetry/HealthTelemetry.cpp @@ -0,0 +1,249 @@ +#include "configuration.h" + +#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR && !defined(ARCH_PORTDUINO) + +#include "../mesh/generated/meshtastic/telemetry.pb.h" +#include "Default.h" +#include "HealthTelemetry.h" +#include "MeshService.h" +#include "NodeDB.h" +#include "PowerFSM.h" +#include "RTC.h" +#include "Router.h" +#include "UnitConversions.h" +#include "main.h" +#include "power.h" +#include "sleep.h" +#include "target_specific.h" +#include +#include + +// Sensors +#include "Sensor/MAX30102Sensor.h" +#include "Sensor/MLX90614Sensor.h" + +MAX30102Sensor max30102Sensor; +MLX90614Sensor mlx90614Sensor; + +#define FAILED_STATE_SENSOR_READ_MULTIPLIER 10 +#define DISPLAY_RECEIVEID_MEASUREMENTS_ON_SCREEN true + +#if (HAS_SCREEN) +#include "graphics/ScreenFonts.h" +#endif +#include + +int32_t HealthTelemetryModule::runOnce() +{ + if (sleepOnNextExecution == true) { + sleepOnNextExecution = false; + uint32_t nightyNightMs = Default::getConfiguredOrDefaultMs(moduleConfig.telemetry.health_update_interval, + default_telemetry_broadcast_interval_secs); + LOG_DEBUG("Sleeping for %ims, then awaking to send metrics again.\n", nightyNightMs); + doDeepSleep(nightyNightMs, true); + } + + uint32_t result = UINT32_MAX; + + if (!(moduleConfig.telemetry.health_measurement_enabled || moduleConfig.telemetry.health_screen_enabled)) { + // If this module is not enabled, and the user doesn't want the display screen don't waste any OSThread time on it + return disable(); + } + + if (firstTime) { + // This is the first time the OSThread library has called this function, so do some setup + firstTime = false; + + if (moduleConfig.telemetry.health_measurement_enabled) { + LOG_INFO("Health Telemetry: Initializing\n"); + // Initialize sensors + if (mlx90614Sensor.hasSensor()) + result = mlx90614Sensor.runOnce(); + if (max30102Sensor.hasSensor()) + result = max30102Sensor.runOnce(); + } + return result; + } else { + // if we somehow got to a second run of this module with measurement disabled, then just wait forever + if (!moduleConfig.telemetry.health_measurement_enabled) { + return disable(); + } + + if (((lastSentToMesh == 0) || + !Throttle::isWithinTimespanMs(lastSentToMesh, Default::getConfiguredOrDefaultMsScaled( + moduleConfig.telemetry.health_update_interval, + default_telemetry_broadcast_interval_secs, numOnlineNodes))) && + airTime->isTxAllowedChannelUtil(config.device.role != meshtastic_Config_DeviceConfig_Role_SENSOR) && + airTime->isTxAllowedAirUtil()) { + sendTelemetry(); + lastSentToMesh = millis(); + } else if (((lastSentToPhone == 0) || !Throttle::isWithinTimespanMs(lastSentToPhone, sendToPhoneIntervalMs)) && + (service->isToPhoneQueueEmpty())) { + // Just send to phone when it's not our time to send to mesh yet + // Only send while queue is empty (phone assumed connected) + sendTelemetry(NODENUM_BROADCAST, true); + lastSentToPhone = millis(); + } + } + return min(sendToPhoneIntervalMs, result); +} + +bool HealthTelemetryModule::wantUIFrame() +{ + return moduleConfig.telemetry.health_screen_enabled; +} + +void HealthTelemetryModule::drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y) +{ + display->setTextAlignment(TEXT_ALIGN_LEFT); + display->setFont(FONT_SMALL); + + if (lastMeasurementPacket == nullptr) { + // If there's no valid packet, display "Health" + display->drawString(x, y, "Health"); + display->drawString(x, y += _fontHeight(FONT_SMALL), "No measurement"); + return; + } + + // Decode the last measurement packet + meshtastic_Telemetry lastMeasurement; + uint32_t agoSecs = service->GetTimeSinceMeshPacket(lastMeasurementPacket); + const char *lastSender = getSenderShortName(*lastMeasurementPacket); + + const meshtastic_Data &p = lastMeasurementPacket->decoded; + if (!pb_decode_from_bytes(p.payload.bytes, p.payload.size, &meshtastic_Telemetry_msg, &lastMeasurement)) { + display->drawString(x, y, "Measurement Error"); + LOG_ERROR("Unable to decode last packet"); + return; + } + + // Display "Health From: ..." on its own + display->drawString(x, y, "Health From: " + String(lastSender) + "(" + String(agoSecs) + "s)"); + + String last_temp = String(lastMeasurement.variant.health_metrics.temperature, 0) + "°C"; + if (moduleConfig.telemetry.environment_display_fahrenheit) { + last_temp = String(UnitConversions::CelsiusToFahrenheit(lastMeasurement.variant.health_metrics.temperature), 0) + "°F"; + } + + // Continue with the remaining details + display->drawString(x, y += _fontHeight(FONT_SMALL), "Temp: " + last_temp); + if (lastMeasurement.variant.health_metrics.has_heart_bpm) { + display->drawString(x, y += _fontHeight(FONT_SMALL), + "Heart Rate: " + String(lastMeasurement.variant.health_metrics.heart_bpm, 0) + " bpm"); + } + if (lastMeasurement.variant.health_metrics.has_spO2) { + display->drawString(x, y += _fontHeight(FONT_SMALL), + "spO2: " + String(lastMeasurement.variant.health_metrics.spO2, 0) + " %"); + } +} + +bool HealthTelemetryModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshtastic_Telemetry *t) +{ + if (t->which_variant == meshtastic_Telemetry_health_metrics_tag) { +#ifdef DEBUG_PORT + const char *sender = getSenderShortName(mp); + + LOG_INFO("(Received from %s): temperature=%f, heart_bpm=%d, spO2=%d,\n", sender, t->variant.health_metrics.temperature, + t->variant.health_metrics.heart_bpm, t->variant.health_metrics.spO2); + +#endif + // release previous packet before occupying a new spot + if (lastMeasurementPacket != nullptr) + packetPool.release(lastMeasurementPacket); + + lastMeasurementPacket = packetPool.allocCopy(mp); + } + + return false; // Let others look at this message also if they want +} + +bool HealthTelemetryModule::getHealthTelemetry(meshtastic_Telemetry *m) +{ + bool valid = true; + bool hasSensor = false; + m->time = getTime(); + m->which_variant = meshtastic_Telemetry_health_metrics_tag; + m->variant.health_metrics = meshtastic_HealthMetrics_init_zero; + + if (max30102Sensor.hasSensor()) { + valid = valid && max30102Sensor.getMetrics(m); + hasSensor = true; + } + if (mlx90614Sensor.hasSensor()) { + valid = valid && mlx90614Sensor.getMetrics(m); + hasSensor = true; + } + + return valid && hasSensor; +} + +meshtastic_MeshPacket *HealthTelemetryModule::allocReply() +{ + if (currentRequest) { + auto req = *currentRequest; + const auto &p = req.decoded; + meshtastic_Telemetry scratch; + meshtastic_Telemetry *decoded = NULL; + memset(&scratch, 0, sizeof(scratch)); + if (pb_decode_from_bytes(p.payload.bytes, p.payload.size, &meshtastic_Telemetry_msg, &scratch)) { + decoded = &scratch; + } else { + LOG_ERROR("Error decoding HealthTelemetry module!\n"); + return NULL; + } + // Check for a request for health metrics + if (decoded->which_variant == meshtastic_Telemetry_health_metrics_tag) { + meshtastic_Telemetry m = meshtastic_Telemetry_init_zero; + if (getHealthTelemetry(&m)) { + LOG_INFO("Health telemetry replying to request\n"); + return allocDataProtobuf(m); + } else { + return NULL; + } + } + } + return NULL; +} + +bool HealthTelemetryModule::sendTelemetry(NodeNum dest, bool phoneOnly) +{ + meshtastic_Telemetry m = meshtastic_Telemetry_init_zero; + m.which_variant = meshtastic_Telemetry_health_metrics_tag; + m.time = getTime(); + if (getHealthTelemetry(&m)) { + LOG_INFO("(Sending): temperature=%f, heart_bpm=%d, spO2=%d\n", m.variant.health_metrics.temperature, + m.variant.health_metrics.heart_bpm, m.variant.health_metrics.spO2); + + sensor_read_error_count = 0; + + meshtastic_MeshPacket *p = allocDataProtobuf(m); + p->to = dest; + p->decoded.want_response = false; + if (config.device.role == meshtastic_Config_DeviceConfig_Role_SENSOR) + p->priority = meshtastic_MeshPacket_Priority_RELIABLE; + else + p->priority = meshtastic_MeshPacket_Priority_BACKGROUND; + // release previous packet before occupying a new spot + if (lastMeasurementPacket != nullptr) + packetPool.release(lastMeasurementPacket); + + lastMeasurementPacket = packetPool.allocCopy(*p); + if (phoneOnly) { + LOG_INFO("Sending packet to phone\n"); + service->sendToPhone(p); + } else { + LOG_INFO("Sending packet to mesh\n"); + service->sendToMesh(p, RX_SRC_LOCAL, true); + + if (config.device.role == meshtastic_Config_DeviceConfig_Role_SENSOR && config.power.is_power_saving) { + LOG_DEBUG("Starting next execution in 5 seconds and then going to sleep.\n"); + sleepOnNextExecution = true; + setIntervalFromNow(5000); + } + } + return true; + } + return false; +} + +#endif diff --git a/src/modules/Telemetry/HealthTelemetry.h b/src/modules/Telemetry/HealthTelemetry.h new file mode 100644 index 000000000..4ad0da838 --- /dev/null +++ b/src/modules/Telemetry/HealthTelemetry.h @@ -0,0 +1,60 @@ +#include "configuration.h" + +#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR && !defined(ARCH_PORTDUINO) + +#pragma once +#include "../mesh/generated/meshtastic/telemetry.pb.h" +#include "NodeDB.h" +#include "ProtobufModule.h" +#include +#include + +class HealthTelemetryModule : private concurrency::OSThread, public ProtobufModule +{ + CallbackObserver nodeStatusObserver = + CallbackObserver(this, &HealthTelemetryModule::handleStatusUpdate); + + public: + HealthTelemetryModule() + : concurrency::OSThread("HealthTelemetryModule"), + ProtobufModule("HealthTelemetry", meshtastic_PortNum_TELEMETRY_APP, &meshtastic_Telemetry_msg) + { + lastMeasurementPacket = nullptr; + nodeStatusObserver.observe(&nodeStatus->onNewStatus); + setIntervalFromNow(10 * 1000); + } + +#if !HAS_SCREEN + void drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y); +#else + virtual void drawFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, int16_t y) override; +#endif + + virtual bool wantUIFrame() override; + + protected: + /** Called to handle a particular incoming message + @return true if you've guaranteed you've handled this message and no other handlers should be considered for it + */ + virtual bool handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshtastic_Telemetry *p) override; + virtual int32_t runOnce() override; + /** Called to get current Health telemetry data + @return true if it contains valid data + */ + bool getHealthTelemetry(meshtastic_Telemetry *m); + virtual meshtastic_MeshPacket *allocReply() override; + /** + * Send our Telemetry into the mesh + */ + bool sendTelemetry(NodeNum dest = NODENUM_BROADCAST, bool wantReplies = false); + + private: + bool firstTime = 1; + meshtastic_MeshPacket *lastMeasurementPacket; + uint32_t sendToPhoneIntervalMs = SECONDS_IN_MINUTE * 1000; // Send to phone every minute + uint32_t lastSentToMesh = 0; + uint32_t lastSentToPhone = 0; + uint32_t sensor_read_error_count = 0; +}; + +#endif diff --git a/src/modules/Telemetry/Sensor/MAX30102Sensor.cpp b/src/modules/Telemetry/Sensor/MAX30102Sensor.cpp new file mode 100644 index 000000000..b3b20e5f2 --- /dev/null +++ b/src/modules/Telemetry/Sensor/MAX30102Sensor.cpp @@ -0,0 +1,83 @@ +#include "configuration.h" + +#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR && !defined(ARCH_PORTDUINO) + +#include "../mesh/generated/meshtastic/telemetry.pb.h" +#include "MAX30102Sensor.h" +#include "TelemetrySensor.h" +#include + +MAX30102Sensor::MAX30102Sensor() : TelemetrySensor(meshtastic_TelemetrySensorType_MAX30102, "MAX30102") {} + +int32_t MAX30102Sensor::runOnce() +{ + LOG_INFO("Init sensor: %s\n", sensorName); + if (!hasSensor()) { + return DEFAULT_SENSOR_MINIMUM_WAIT_TIME_BETWEEN_READS; + } + + if (max30102.begin(*nodeTelemetrySensorsMap[sensorType].second, _speed, nodeTelemetrySensorsMap[sensorType].first) == + true) // MAX30102 init + { + byte brightness = 60; // 0=Off to 255=50mA + byte sampleAverage = 4; // 1, 2, 4, 8, 16, 32 + byte leds = 2; // 1 = Red only, 2 = Red + IR + byte sampleRate = 100; // 50, 100, 200, 400, 800, 1000, 1600, 3200 + int pulseWidth = 411; // 69, 118, 215, 411 + int adcRange = 4096; // 2048, 4096, 8192, 16384 + + max30102.enableDIETEMPRDY(); // Enable the temperature ready interrupt + max30102.setup(brightness, sampleAverage, leds, sampleRate, pulseWidth, adcRange); + LOG_DEBUG("MAX30102 Init Succeed\n"); + status = true; + } else { + LOG_ERROR("MAX30102 Init Failed\n"); + status = false; + } + return initI2CSensor(); +} + +void MAX30102Sensor::setup() {} + +bool MAX30102Sensor::getMetrics(meshtastic_Telemetry *measurement) +{ + uint32_t ir_buff[MAX30102_BUFFER_LEN]; + uint32_t red_buff[MAX30102_BUFFER_LEN]; + int32_t spo2; + int8_t spo2_valid; + int32_t heart_rate; + int8_t heart_rate_valid; + float temp = max30102.readTemperature(); + + measurement->variant.environment_metrics.temperature = temp; + measurement->variant.environment_metrics.has_temperature = true; + measurement->variant.health_metrics.temperature = temp; + measurement->variant.health_metrics.has_temperature = true; + for (byte i = 0; i < MAX30102_BUFFER_LEN; i++) { + while (max30102.available() == false) + max30102.check(); + + red_buff[i] = max30102.getRed(); + ir_buff[i] = max30102.getIR(); + max30102.nextSample(); + } + + maxim_heart_rate_and_oxygen_saturation(ir_buff, MAX30102_BUFFER_LEN, red_buff, &spo2, &spo2_valid, &heart_rate, + &heart_rate_valid); + LOG_DEBUG("heart_rate=%d(%d), sp02=%d(%d)", heart_rate, heart_rate_valid, spo2, spo2_valid); + if (heart_rate_valid) { + measurement->variant.health_metrics.has_heart_bpm = true; + measurement->variant.health_metrics.heart_bpm = heart_rate; + } else { + measurement->variant.health_metrics.has_heart_bpm = false; + } + if (spo2_valid) { + measurement->variant.health_metrics.has_spO2 = true; + measurement->variant.health_metrics.spO2 = spo2; + } else { + measurement->variant.health_metrics.has_spO2 = true; + } + return true; +} + +#endif diff --git a/src/modules/Telemetry/Sensor/MAX30102Sensor.h b/src/modules/Telemetry/Sensor/MAX30102Sensor.h new file mode 100644 index 000000000..426d9d365 --- /dev/null +++ b/src/modules/Telemetry/Sensor/MAX30102Sensor.h @@ -0,0 +1,26 @@ +#include "configuration.h" + +#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR && !defined(ARCH_PORTDUINO) + +#include "../mesh/generated/meshtastic/telemetry.pb.h" +#include "TelemetrySensor.h" +#include + +#define MAX30102_BUFFER_LEN 100 + +class MAX30102Sensor : public TelemetrySensor +{ + private: + MAX30105 max30102 = MAX30105(); + uint32_t _speed = 200000UL; + + protected: + virtual void setup() override; + + public: + MAX30102Sensor(); + virtual int32_t runOnce() override; + virtual bool getMetrics(meshtastic_Telemetry *measurement) override; +}; + +#endif diff --git a/src/modules/Telemetry/Sensor/MLX90614Sensor.cpp b/src/modules/Telemetry/Sensor/MLX90614Sensor.cpp new file mode 100644 index 000000000..92c22bf21 --- /dev/null +++ b/src/modules/Telemetry/Sensor/MLX90614Sensor.cpp @@ -0,0 +1,44 @@ +#include "configuration.h" + +#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR && !defined(ARCH_PORTDUINO) + +#include "../mesh/generated/meshtastic/telemetry.pb.h" +#include "MLX90614Sensor.h" +#include "TelemetrySensor.h" +MLX90614Sensor::MLX90614Sensor() : TelemetrySensor(meshtastic_TelemetrySensorType_MLX90614, "MLX90614") {} + +int32_t MLX90614Sensor::runOnce() +{ + LOG_INFO("Init sensor: %s\n", sensorName); + if (!hasSensor()) { + return DEFAULT_SENSOR_MINIMUM_WAIT_TIME_BETWEEN_READS; + } + + if (mlx.begin(nodeTelemetrySensorsMap[sensorType].first, nodeTelemetrySensorsMap[sensorType].second) == true) // MLX90614 init + { + LOG_DEBUG("MLX90614 emissivity: %f", mlx.readEmissivity()); + if (fabs(MLX90614_EMISSIVITY - mlx.readEmissivity()) > 0.001) { + mlx.writeEmissivity(MLX90614_EMISSIVITY); + LOG_INFO("MLX90614 emissivity updated. In case of weird data, power cycle."); + } + LOG_DEBUG("MLX90614 Init Succeed\n"); + status = true; + } else { + LOG_ERROR("MLX90614 Init Failed\n"); + status = false; + } + return initI2CSensor(); +} + +void MLX90614Sensor::setup() {} + +bool MLX90614Sensor::getMetrics(meshtastic_Telemetry *measurement) +{ + measurement->variant.environment_metrics.temperature = mlx.readAmbientTempC(); + measurement->variant.environment_metrics.has_temperature = true; + measurement->variant.health_metrics.temperature = mlx.readObjectTempC(); + measurement->variant.health_metrics.has_temperature = true; + return true; +} + +#endif diff --git a/src/modules/Telemetry/Sensor/MLX90614Sensor.h b/src/modules/Telemetry/Sensor/MLX90614Sensor.h new file mode 100644 index 000000000..00f63449e --- /dev/null +++ b/src/modules/Telemetry/Sensor/MLX90614Sensor.h @@ -0,0 +1,24 @@ +#include "configuration.h" + +#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR && !defined(ARCH_PORTDUINO) +#include "../mesh/generated/meshtastic/telemetry.pb.h" +#include "TelemetrySensor.h" +#include + +#define MLX90614_EMISSIVITY 0.98 // human skin + +class MLX90614Sensor : public TelemetrySensor +{ + private: + Adafruit_MLX90614 mlx = Adafruit_MLX90614(); + + protected: + virtual void setup() override; + + public: + MLX90614Sensor(); + virtual int32_t runOnce() override; + virtual bool getMetrics(meshtastic_Telemetry *measurement) override; +}; + +#endif From 37f294d0a6b4d8d224c0383632747fce3796c320 Mon Sep 17 00:00:00 2001 From: jhps Date: Mon, 7 Oct 2024 18:39:59 -0700 Subject: [PATCH 83/88] In shutdown, on button press, wake back to application rather than into the loader. (#4997) Suggested by lyusupov and implemented by todd-herbert. https://github.com/meshtastic/firmware/issues/4651 --- src/platform/nrf52/main-nrf52.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/src/platform/nrf52/main-nrf52.cpp b/src/platform/nrf52/main-nrf52.cpp index 4023a3cb9..f9329d875 100644 --- a/src/platform/nrf52/main-nrf52.cpp +++ b/src/platform/nrf52/main-nrf52.cpp @@ -270,6 +270,11 @@ void cpuDeepSleep(uint32_t msecToWake) delay(msecToWake); NVIC_SystemReset(); } else { + // Resume on user button press + // https://github.com/lyusupov/SoftRF/blob/81c519ca75693b696752235d559e881f2e0511ee/software/firmware/source/SoftRF/src/platform/nRF52.cpp#L1738 + constexpr uint32_t DFU_MAGIC_SKIP = 0x6d; + sd_power_gpregret_set(0, DFU_MAGIC_SKIP); // Equivalent NRF_POWER->GPREGRET = DFU_MAGIC_SKIP + // FIXME, use system off mode with ram retention for key state? // FIXME, use non-init RAM per // https://devzone.nordicsemi.com/f/nordic-q-a/48919/ram-retention-settings-with-softdevice-enabled From 2e5399dbe46b548c0b567a7ea120e5f7ee224f19 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Tue, 8 Oct 2024 05:03:43 -0500 Subject: [PATCH 84/88] De-conflict MLX90614_ADDR macro --- src/configuration.h | 2 +- src/detect/ScanI2CTwoWire.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/configuration.h b/src/configuration.h index 975c9fc68..729d6b046 100644 --- a/src/configuration.h +++ b/src/configuration.h @@ -145,7 +145,7 @@ along with this program. If not, see . #define DFROBOT_LARK_ADDR 0x42 #define NAU7802_ADDR 0x2A #define MAX30102_ADDR 0x57 -#define MLX90614_ADDR 0x5A +#define MLX90614_ADDR_DEF 0x5A // ----------------------------------------------------------------------------- // ACCELEROMETER diff --git a/src/detect/ScanI2CTwoWire.cpp b/src/detect/ScanI2CTwoWire.cpp index 74597fbc3..3f4f88f74 100644 --- a/src/detect/ScanI2CTwoWire.cpp +++ b/src/detect/ScanI2CTwoWire.cpp @@ -405,7 +405,7 @@ void ScanI2CTwoWire::scanPort(I2CPort port, uint8_t *address, uint8_t asize) SCAN_SIMPLE_CASE(NAU7802_ADDR, NAU7802, "NAU7802 based scale found\n"); SCAN_SIMPLE_CASE(FT6336U_ADDR, FT6336U, "FT6336U touchscreen found\n"); SCAN_SIMPLE_CASE(MAX1704X_ADDR, MAX17048, "MAX17048 lipo fuel gauge found\n"); - SCAN_SIMPLE_CASE(MLX90614_ADDR, MLX90614, "MLX90614 IR temp sensor found\n"); + SCAN_SIMPLE_CASE(MLX90614_ADDR_DEF, MLX90614, "MLX90614 IR temp sensor found\n"); case ICM20948_ADDR: // same as BMX160_ADDR case ICM20948_ADDR_ALT: // same as MPU6050_ADDR From a0dd7b43d56c5a78d6e7f58ad1c355c95720be89 Mon Sep 17 00:00:00 2001 From: TheMalkavien Date: Tue, 8 Oct 2024 12:24:37 +0200 Subject: [PATCH 85/88] First version of a DeepSleep state for the RP2040 (#4976) * Adding pico-extra utils * RP2040 can now go to deepsleep * First RP2040 DeepSleep code - TODO : do better and restore * FIX RAK11310 compilation (revert SDK + missing defines) --------- Co-authored-by: Ben Meadors --- arch/rp2xx0/rp2040.ini | 6 +- src/Power.cpp | 2 +- .../hardware_rosc/include/hardware/rosc.h | 90 ++++++++++ src/platform/rp2xx0/hardware_rosc/rosc.c | 61 +++++++ src/platform/rp2xx0/main-rp2xx0.cpp | 57 ++++++- .../rp2xx0/pico_sleep/include/pico/sleep.h | 107 ++++++++++++ src/platform/rp2xx0/pico_sleep/sleep.c | 159 ++++++++++++++++++ src/shutdown.h | 2 +- variants/rak11310/platformio.ini | 2 + variants/rak11310/variant.h | 1 + variants/rp2040-lora/variant.h | 1 + 11 files changed, 479 insertions(+), 9 deletions(-) create mode 100644 src/platform/rp2xx0/hardware_rosc/include/hardware/rosc.h create mode 100644 src/platform/rp2xx0/hardware_rosc/rosc.c create mode 100644 src/platform/rp2xx0/pico_sleep/include/pico/sleep.h create mode 100644 src/platform/rp2xx0/pico_sleep/sleep.c diff --git a/arch/rp2xx0/rp2040.ini b/arch/rp2xx0/rp2040.ini index 5b4ec74d2..c004a3bec 100644 --- a/arch/rp2xx0/rp2040.ini +++ b/arch/rp2xx0/rp2040.ini @@ -1,14 +1,16 @@ ; Common settings for rp2040 Processor based targets [rp2040_base] -platform = https://github.com/maxgerhardt/platform-raspberrypi.git#60d6ae81fcc73c34b1493ca9e261695e471bc0c2 +platform = https://github.com/maxgerhardt/platform-raspberrypi.git#v1.2.0-gcc12 extends = arduino_base -platform_packages = framework-arduinopico@https://github.com/earlephilhower/arduino-pico.git#3.7.2 +platform_packages = framework-arduinopico@https://github.com/earlephilhower/arduino-pico.git#4.0.3 board_build.core = earlephilhower board_build.filesystem_size = 0.5m build_flags = ${arduino_base.build_flags} -Wno-unused-variable -Wcast-align -Isrc/platform/rp2xx0 + -Isrc/platform/rp2xx0/hardware_rosc/include + -Isrc/platform/rp2xx0/pico_sleep/include -D__PLAT_RP2040__ # -D _POSIX_THREADS build_src_filter = diff --git a/src/Power.cpp b/src/Power.cpp index 2f5f441ae..2fe28633a 100644 --- a/src/Power.cpp +++ b/src/Power.cpp @@ -588,7 +588,7 @@ void Power::shutdown() { LOG_INFO("Shutting down\n"); -#if defined(ARCH_NRF52) || defined(ARCH_ESP32) +#if defined(ARCH_NRF52) || defined(ARCH_ESP32) || defined(ARCH_RP2040) #ifdef PIN_LED1 ledOff(PIN_LED1); #endif diff --git a/src/platform/rp2xx0/hardware_rosc/include/hardware/rosc.h b/src/platform/rp2xx0/hardware_rosc/include/hardware/rosc.h new file mode 100644 index 000000000..2720f0b93 --- /dev/null +++ b/src/platform/rp2xx0/hardware_rosc/include/hardware/rosc.h @@ -0,0 +1,90 @@ +/* + * Copyright (c) 2020 Raspberry Pi (Trading) Ltd. + * + * SPDX-License-Identifier: BSD-3-Clause + */ + +#ifndef _HARDWARE_ROSC_H_ +#define _HARDWARE_ROSC_H_ + +#include "pico.h" +#include "hardware/structs/rosc.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/** \file rosc.h + * \defgroup hardware_rosc hardware_rosc + * + * Ring Oscillator (ROSC) API + * + * A Ring Oscillator is an on-chip oscillator that requires no external crystal. Instead, the output is generated from a series of + * inverters that are chained together to create a feedback loop. RP2040 boots from the ring oscillator initially, meaning the + * first stages of the bootrom, including booting from SPI flash, will be clocked by the ring oscillator. If your design has a + * crystal oscillator, you’ll likely want to switch to this as your reference clock as soon as possible, because the frequency is + * more accurate than the ring oscillator. + */ + +/*! \brief Set frequency of the Ring Oscillator + * \ingroup hardware_rosc + * + * \param code The drive strengths. See the RP2040 datasheet for information on this value. + */ +void rosc_set_freq(uint32_t code); + +/*! \brief Set range of the Ring Oscillator + * \ingroup hardware_rosc + * + * Frequency range. Frequencies will vary with Process, Voltage & Temperature (PVT). + * Clock output will not glitch when changing the range up one step at a time. + * + * \param range 0x01 Low, 0x02 Medium, 0x03 High, 0x04 Too High. + */ +void rosc_set_range(uint range); + +/*! \brief Disable the Ring Oscillator + * \ingroup hardware_rosc + * + */ +void rosc_disable(void); + +/*! \brief Put Ring Oscillator in to dormant mode. + * \ingroup hardware_rosc + * + * The ROSC supports a dormant mode,which stops oscillation until woken up up by an asynchronous interrupt. + * This can either come from the RTC, being clocked by an external clock, or a GPIO pin going high or low. + * If no IRQ is configured before going into dormant mode the ROSC will never restart. + * + * PLLs should be stopped before selecting dormant mode. + */ +void rosc_set_dormant(void); + +// FIXME: Add doxygen + +uint32_t next_rosc_code(uint32_t code); + +uint rosc_find_freq(uint32_t low_mhz, uint32_t high_mhz); + +void rosc_set_div(uint32_t div); + +inline static void rosc_clear_bad_write(void) { + hw_clear_bits(&rosc_hw->status, ROSC_STATUS_BADWRITE_BITS); +} + +inline static bool rosc_write_okay(void) { + return !(rosc_hw->status & ROSC_STATUS_BADWRITE_BITS); +} + +inline static void rosc_write(io_rw_32 *addr, uint32_t value) { + rosc_clear_bad_write(); + assert(rosc_write_okay()); + *addr = value; + assert(rosc_write_okay()); +}; + +#ifdef __cplusplus +} +#endif + +#endif \ No newline at end of file diff --git a/src/platform/rp2xx0/hardware_rosc/rosc.c b/src/platform/rp2xx0/hardware_rosc/rosc.c new file mode 100644 index 000000000..69b6012a1 --- /dev/null +++ b/src/platform/rp2xx0/hardware_rosc/rosc.c @@ -0,0 +1,61 @@ +/* + * Copyright (c) 2020 Raspberry Pi (Trading) Ltd. + * + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include "pico.h" + +// For MHZ definitions etc +#include "hardware/clocks.h" +#include "hardware/rosc.h" + +// Given a ROSC delay stage code, return the next-numerically-higher code. +// Top result bit is set when called on maximum ROSC code. +uint32_t next_rosc_code(uint32_t code) { + return ((code | 0x08888888u) + 1u) & 0xf7777777u; +} + +uint rosc_find_freq(uint32_t low_mhz, uint32_t high_mhz) { + // TODO: This could be a lot better + rosc_set_div(1); + for (uint32_t code = 0; code <= 0x77777777u; code = next_rosc_code(code)) { + rosc_set_freq(code); + uint rosc_mhz = frequency_count_khz(CLOCKS_FC0_SRC_VALUE_ROSC_CLKSRC) / 1000; + if ((rosc_mhz >= low_mhz) && (rosc_mhz <= high_mhz)) { + return rosc_mhz; + } + } + return 0; +} + +void rosc_set_div(uint32_t div) { + assert(div <= 31 && div >= 1); + rosc_write(&rosc_hw->div, ROSC_DIV_VALUE_PASS + div); +} + +void rosc_set_freq(uint32_t code) { + rosc_write(&rosc_hw->freqa, (ROSC_FREQA_PASSWD_VALUE_PASS << ROSC_FREQA_PASSWD_LSB) | (code & 0xffffu)); + rosc_write(&rosc_hw->freqb, (ROSC_FREQA_PASSWD_VALUE_PASS << ROSC_FREQA_PASSWD_LSB) | (code >> 16u)); +} + +void rosc_set_range(uint range) { + // Range should use enumvals from the headers and thus have the password correct + rosc_write(&rosc_hw->ctrl, (ROSC_CTRL_ENABLE_VALUE_ENABLE << ROSC_CTRL_ENABLE_LSB) | range); +} + +void rosc_disable(void) { + uint32_t tmp = rosc_hw->ctrl; + tmp &= (~ROSC_CTRL_ENABLE_BITS); + tmp |= (ROSC_CTRL_ENABLE_VALUE_DISABLE << ROSC_CTRL_ENABLE_LSB); + rosc_write(&rosc_hw->ctrl, tmp); + // Wait for stable to go away + while(rosc_hw->status & ROSC_STATUS_STABLE_BITS); +} + +void rosc_set_dormant(void) { + // WARNING: This stops the rosc until woken up by an irq + rosc_write(&rosc_hw->dormant, ROSC_DORMANT_VALUE_DORMANT); + // Wait for it to become stable once woken up + while(!(rosc_hw->status & ROSC_STATUS_STABLE_BITS)); +} \ No newline at end of file diff --git a/src/platform/rp2xx0/main-rp2xx0.cpp b/src/platform/rp2xx0/main-rp2xx0.cpp index 6306f34c1..60847f318 100644 --- a/src/platform/rp2xx0/main-rp2xx0.cpp +++ b/src/platform/rp2xx0/main-rp2xx0.cpp @@ -4,20 +4,67 @@ #include #include #include -#include +#include void setBluetoothEnable(bool enable) { // not needed } +static bool awake; + +static void sleep_callback(void) { + awake = true; +} + +void epoch_to_datetime(time_t epoch, datetime_t *dt) { + struct tm *tm_info; + + tm_info = gmtime(&epoch); + dt->year = tm_info->tm_year; + dt->month = tm_info->tm_mon + 1; + dt->day = tm_info->tm_mday; + dt->dotw = tm_info->tm_wday; + dt->hour = tm_info->tm_hour; + dt->min = tm_info->tm_min; + dt->sec = tm_info->tm_sec; +} + +void debug_date(datetime_t t) +{ + LOG_DEBUG("%d %d %d %d %d %d %d\n", t.year, t.month, t.day, t.hour, t.min, t.sec, t.dotw); + uart_default_tx_wait_blocking(); +} + void cpuDeepSleep(uint32_t msecs) { - /* Disable both PLL to avoid power dissipation */ - pll_deinit(pll_sys); - pll_deinit(pll_usb); + + time_t seconds = (time_t)(msecs/1000); + datetime_t t_init, t_alarm; + + awake = false; + // Start the RTC + rtc_init(); + epoch_to_datetime(0, &t_init); + rtc_set_datetime(&t_init); + epoch_to_datetime(seconds, &t_alarm); + // debug_date(t_init); + // debug_date(t_alarm); + uart_default_tx_wait_blocking(); + sleep_run_from_dormant_source(DORMANT_SOURCE_ROSC); + sleep_goto_sleep_until(&t_alarm, &sleep_callback); + + // Make sure we don't wake + while (!awake) { + delay(1); + } + + /* For now, I don't know how to revert this state + We just reboot in order to get back operational */ + rp2040.reboot(); + /* Set RP2040 in dormant mode. Will not wake up. */ - xosc_dormant(); + // xosc_dormant(); } void updateBatteryLevel(uint8_t level) diff --git a/src/platform/rp2xx0/pico_sleep/include/pico/sleep.h b/src/platform/rp2xx0/pico_sleep/include/pico/sleep.h new file mode 100644 index 000000000..b97a23169 --- /dev/null +++ b/src/platform/rp2xx0/pico_sleep/include/pico/sleep.h @@ -0,0 +1,107 @@ +/* + * Copyright (c) 2020 Raspberry Pi (Trading) Ltd. + * + * SPDX-License-Identifier: BSD-3-Clause + */ + +#ifndef _PICO_SLEEP_H_ +#define _PICO_SLEEP_H_ + +#include "pico.h" +#include "hardware/rtc.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/** \file sleep.h + * \defgroup hardware_sleep hardware_sleep + * + * Lower Power Sleep API + * + * The difference between sleep and dormant is that ALL clocks are stopped in dormant mode, + * until the source (either xosc or rosc) is started again by an external event. + * In sleep mode some clocks can be left running controlled by the SLEEP_EN registers in the clocks + * block. For example you could keep clk_rtc running. Some destinations (proc0 and proc1 wakeup logic) + * can't be stopped in sleep mode otherwise there wouldn't be enough logic to wake up again. + * + * \subsection sleep_example Example + * \addtogroup hardware_sleep + * \include hello_sleep.c + + */ +typedef enum { + DORMANT_SOURCE_NONE, + DORMANT_SOURCE_XOSC, + DORMANT_SOURCE_ROSC +} dormant_source_t; + +/*! \brief Set all clock sources to the the dormant clock source to prepare for sleep. + * \ingroup hardware_sleep + * + * \param dormant_source The dormant clock source to use + */ +void sleep_run_from_dormant_source(dormant_source_t dormant_source); + +/*! \brief Set the dormant clock source to be the crystal oscillator + * \ingroup hardware_sleep + */ +static inline void sleep_run_from_xosc(void) { + sleep_run_from_dormant_source(DORMANT_SOURCE_XOSC); +} + +/*! \brief Set the dormant clock source to be the ring oscillator + * \ingroup hardware_sleep + */ +static inline void sleep_run_from_rosc(void) { + sleep_run_from_dormant_source(DORMANT_SOURCE_ROSC); +} + +/*! \brief Send system to sleep until the specified time + * \ingroup hardware_sleep + * + * One of the sleep_run_* functions must be called prior to this call + * + * \param t The time to wake up + * \param callback Function to call on wakeup. + */ +void sleep_goto_sleep_until(datetime_t *t, rtc_callback_t callback); + +/*! \brief Send system to sleep until the specified GPIO changes + * \ingroup hardware_sleep + * + * One of the sleep_run_* functions must be called prior to this call + * + * \param gpio_pin The pin to provide the wake up + * \param edge true for leading edge, false for trailing edge + * \param high true for active high, false for active low + */ +void sleep_goto_dormant_until_pin(uint gpio_pin, bool edge, bool high); + +/*! \brief Send system to sleep until a leading high edge is detected on GPIO + * \ingroup hardware_sleep + * + * One of the sleep_run_* functions must be called prior to this call + * + * \param gpio_pin The pin to provide the wake up + */ +static inline void sleep_goto_dormant_until_edge_high(uint gpio_pin) { + sleep_goto_dormant_until_pin(gpio_pin, true, true); +} + +/*! \brief Send system to sleep until a high level is detected on GPIO + * \ingroup hardware_sleep + * + * One of the sleep_run_* functions must be called prior to this call + * + * \param gpio_pin The pin to provide the wake up + */ +static inline void sleep_goto_dormant_until_level_high(uint gpio_pin) { + sleep_goto_dormant_until_pin(gpio_pin, false, true); +} + +#ifdef __cplusplus +} +#endif + +#endif \ No newline at end of file diff --git a/src/platform/rp2xx0/pico_sleep/sleep.c b/src/platform/rp2xx0/pico_sleep/sleep.c new file mode 100644 index 000000000..1bb8db699 --- /dev/null +++ b/src/platform/rp2xx0/pico_sleep/sleep.c @@ -0,0 +1,159 @@ +/* + * Copyright (c) 2020 Raspberry Pi (Trading) Ltd. + * + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include "pico.h" + +#include "pico/stdlib.h" +#include "pico/sleep.h" + +#include "hardware/rtc.h" +#include "hardware/pll.h" +#include "hardware/clocks.h" +#include "hardware/xosc.h" +#include "hardware/rosc.h" +#include "hardware/regs/io_bank0.h" +// For __wfi +#include "hardware/sync.h" +// For scb_hw so we can enable deep sleep +#include "hardware/structs/scb.h" +// when using old SDK this macro is not defined +#ifndef XOSC_HZ + #define XOSC_HZ 12000000u +#endif +// The difference between sleep and dormant is that ALL clocks are stopped in dormant mode, +// until the source (either xosc or rosc) is started again by an external event. +// In sleep mode some clocks can be left running controlled by the SLEEP_EN registers in the clocks +// block. For example you could keep clk_rtc running. Some destinations (proc0 and proc1 wakeup logic) +// can't be stopped in sleep mode otherwise there wouldn't be enough logic to wake up again. + + +// TODO: Optionally, memories can also be powered down. + +static dormant_source_t _dormant_source; + +bool dormant_source_valid(dormant_source_t dormant_source) { + return (dormant_source == DORMANT_SOURCE_XOSC) || (dormant_source == DORMANT_SOURCE_ROSC); +} + +// In order to go into dormant mode we need to be running from a stoppable clock source: +// either the xosc or rosc with no PLLs running. This means we disable the USB and ADC clocks +// and all PLLs +void sleep_run_from_dormant_source(dormant_source_t dormant_source) { + assert(dormant_source_valid(dormant_source)); + _dormant_source = dormant_source; + + // FIXME: Just defining average rosc freq here. + uint src_hz = (dormant_source == DORMANT_SOURCE_XOSC) ? XOSC_HZ : 6.5 * MHZ; + uint clk_ref_src = (dormant_source == DORMANT_SOURCE_XOSC) ? + CLOCKS_CLK_REF_CTRL_SRC_VALUE_XOSC_CLKSRC : + CLOCKS_CLK_REF_CTRL_SRC_VALUE_ROSC_CLKSRC_PH; + + // CLK_REF = XOSC or ROSC + clock_configure(clk_ref, + clk_ref_src, + 0, // No aux mux + src_hz, + src_hz); + + // CLK SYS = CLK_REF + clock_configure(clk_sys, + CLOCKS_CLK_SYS_CTRL_SRC_VALUE_CLK_REF, + 0, // Using glitchless mux + src_hz, + src_hz); + + // CLK USB = 0MHz + clock_stop(clk_usb); + + // CLK ADC = 0MHz + clock_stop(clk_adc); + + // CLK RTC = ideally XOSC (12MHz) / 256 = 46875Hz but could be rosc + uint clk_rtc_src = (dormant_source == DORMANT_SOURCE_XOSC) ? + CLOCKS_CLK_RTC_CTRL_AUXSRC_VALUE_XOSC_CLKSRC : + CLOCKS_CLK_RTC_CTRL_AUXSRC_VALUE_ROSC_CLKSRC_PH; + + clock_configure(clk_rtc, + 0, // No GLMUX + clk_rtc_src, + src_hz, + 46875); + + // CLK PERI = clk_sys. Used as reference clock for Peripherals. No dividers so just select and enable + clock_configure(clk_peri, + 0, + CLOCKS_CLK_PERI_CTRL_AUXSRC_VALUE_CLK_SYS, + src_hz, + src_hz); + + pll_deinit(pll_sys); + pll_deinit(pll_usb); + + // Assuming both xosc and rosc are running at the moment + if (dormant_source == DORMANT_SOURCE_XOSC) { + // Can disable rosc + rosc_disable(); + } else { + // Can disable xosc + xosc_disable(); + } + + // Reconfigure uart with new clocks + /* This dones not work with our current core */ + //setup_default_uart(); +} + +// Go to sleep until woken up by the RTC +void sleep_goto_sleep_until(datetime_t *t, rtc_callback_t callback) { + // We should have already called the sleep_run_from_dormant_source function + assert(dormant_source_valid(_dormant_source)); + + // Turn off all clocks when in sleep mode except for RTC + clocks_hw->sleep_en0 = CLOCKS_SLEEP_EN0_CLK_RTC_RTC_BITS; + clocks_hw->sleep_en1 = 0x0; + + rtc_set_alarm(t, callback); + + uint save = scb_hw->scr; + // Enable deep sleep at the proc + scb_hw->scr = save | M0PLUS_SCR_SLEEPDEEP_BITS; + + // Go to sleep + __wfi(); +} + +static void _go_dormant(void) { + assert(dormant_source_valid(_dormant_source)); + + if (_dormant_source == DORMANT_SOURCE_XOSC) { + xosc_dormant(); + } else { + rosc_set_dormant(); + } +} + +void sleep_goto_dormant_until_pin(uint gpio_pin, bool edge, bool high) { + bool low = !high; + bool level = !edge; + + // Configure the appropriate IRQ at IO bank 0 + assert(gpio_pin < NUM_BANK0_GPIOS); + + uint32_t event = 0; + + if (level && low) event = IO_BANK0_DORMANT_WAKE_INTE0_GPIO0_LEVEL_LOW_BITS; + if (level && high) event = IO_BANK0_DORMANT_WAKE_INTE0_GPIO0_LEVEL_HIGH_BITS; + if (edge && high) event = IO_BANK0_DORMANT_WAKE_INTE0_GPIO0_EDGE_HIGH_BITS; + if (edge && low) event = IO_BANK0_DORMANT_WAKE_INTE0_GPIO0_EDGE_LOW_BITS; + + gpio_set_dormant_irq_enabled(gpio_pin, event, true); + + _go_dormant(); + // Execution stops here until woken up + + // Clear the irq so we can go back to dormant mode again if we want + gpio_acknowledge_irq(gpio_pin, event); +} \ No newline at end of file diff --git a/src/shutdown.h b/src/shutdown.h index 3f191eea8..481e7778d 100644 --- a/src/shutdown.h +++ b/src/shutdown.h @@ -44,7 +44,7 @@ void powerCommandsCheck() if (shutdownAtMsec && millis() > shutdownAtMsec) { LOG_INFO("Shutting down from admin command\n"); -#if defined(ARCH_NRF52) || defined(ARCH_ESP32) +#if defined(ARCH_NRF52) || defined(ARCH_ESP32) || defined(ARCH_RP2040) playShutdownMelody(); power->shutdown(); #elif defined(ARCH_PORTDUINO) diff --git a/variants/rak11310/platformio.ini b/variants/rak11310/platformio.ini index e1bd2b1b0..c7b3504fe 100644 --- a/variants/rak11310/platformio.ini +++ b/variants/rak11310/platformio.ini @@ -2,6 +2,8 @@ extends = rp2040_base board = wiscore_rak11300 upload_protocol = picotool +# keep an old SDK to use less memory. +platform_packages = framework-arduinopico@https://github.com/earlephilhower/arduino-pico.git#3.7.2 # add our variants files to the include and src paths build_flags = ${rp2040_base.build_flags} diff --git a/variants/rak11310/variant.h b/variants/rak11310/variant.h index f9dcbd91a..54e403ee7 100644 --- a/variants/rak11310/variant.h +++ b/variants/rak11310/variant.h @@ -6,6 +6,7 @@ #define LED_CONN PIN_LED2 #define LED_PIN LED_BUILTIN +#define ledOff(pin) pinMode(pin, INPUT) #define BUTTON_PIN 9 #define BUTTON_NEED_PULLUP diff --git a/variants/rp2040-lora/variant.h b/variants/rp2040-lora/variant.h index d0bbc0ec3..f1826605f 100644 --- a/variants/rp2040-lora/variant.h +++ b/variants/rp2040-lora/variant.h @@ -23,6 +23,7 @@ // ratio of voltage divider = 3.0 (R17=200k, R18=100k) // #define ADC_MULTIPLIER 3.1 // 3.0 + a bit for being optimistic +#define HAS_CPU_SHUTDOWN 1 #define USE_SX1262 #undef LORA_SCK From a05b009379fc15ddcbc08a0af096d9fbb8697554 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Tue, 8 Oct 2024 05:33:38 -0500 Subject: [PATCH 86/88] Posthumous tronkination --- src/mesh/RadioInterface.h | 4 +- .../hardware_rosc/include/hardware/rosc.h | 11 ++- src/platform/rp2xx0/hardware_rosc/rosc.c | 27 ++++--- src/platform/rp2xx0/main-rp2xx0.cpp | 12 +-- .../rp2xx0/pico_sleep/include/pico/sleep.h | 20 ++--- src/platform/rp2xx0/pico_sleep/sleep.c | 74 +++++++++---------- 6 files changed, 79 insertions(+), 69 deletions(-) diff --git a/src/mesh/RadioInterface.h b/src/mesh/RadioInterface.h index 6df51ce1a..89a4c7087 100644 --- a/src/mesh/RadioInterface.h +++ b/src/mesh/RadioInterface.h @@ -55,7 +55,7 @@ typedef struct { PacketHeader header; /** The payload, of maximum length minus the header, aligned just to be sure */ - uint8_t payload[MAX_LORA_PAYLOAD_LEN + 1 - sizeof(PacketHeader)] __attribute__ ((__aligned__)); + uint8_t payload[MAX_LORA_PAYLOAD_LEN + 1 - sizeof(PacketHeader)] __attribute__((__aligned__)); } RadioBuffer; @@ -105,7 +105,7 @@ class RadioInterface /** * A temporary buffer used for sending/receiving packets, sized to hold the biggest buffer we might need * */ - RadioBuffer radioBuffer __attribute__ ((__aligned__)); + RadioBuffer radioBuffer __attribute__((__aligned__)); /** * Enqueue a received packet for the registered receiver */ diff --git a/src/platform/rp2xx0/hardware_rosc/include/hardware/rosc.h b/src/platform/rp2xx0/hardware_rosc/include/hardware/rosc.h index 2720f0b93..e1e014f33 100644 --- a/src/platform/rp2xx0/hardware_rosc/include/hardware/rosc.h +++ b/src/platform/rp2xx0/hardware_rosc/include/hardware/rosc.h @@ -7,8 +7,8 @@ #ifndef _HARDWARE_ROSC_H_ #define _HARDWARE_ROSC_H_ -#include "pico.h" #include "hardware/structs/rosc.h" +#include "pico.h" #ifdef __cplusplus extern "C" { @@ -68,15 +68,18 @@ uint rosc_find_freq(uint32_t low_mhz, uint32_t high_mhz); void rosc_set_div(uint32_t div); -inline static void rosc_clear_bad_write(void) { +inline static void rosc_clear_bad_write(void) +{ hw_clear_bits(&rosc_hw->status, ROSC_STATUS_BADWRITE_BITS); } -inline static bool rosc_write_okay(void) { +inline static bool rosc_write_okay(void) +{ return !(rosc_hw->status & ROSC_STATUS_BADWRITE_BITS); } -inline static void rosc_write(io_rw_32 *addr, uint32_t value) { +inline static void rosc_write(io_rw_32 *addr, uint32_t value) +{ rosc_clear_bad_write(); assert(rosc_write_okay()); *addr = value; diff --git a/src/platform/rp2xx0/hardware_rosc/rosc.c b/src/platform/rp2xx0/hardware_rosc/rosc.c index 69b6012a1..f79929f8d 100644 --- a/src/platform/rp2xx0/hardware_rosc/rosc.c +++ b/src/platform/rp2xx0/hardware_rosc/rosc.c @@ -12,11 +12,13 @@ // Given a ROSC delay stage code, return the next-numerically-higher code. // Top result bit is set when called on maximum ROSC code. -uint32_t next_rosc_code(uint32_t code) { +uint32_t next_rosc_code(uint32_t code) +{ return ((code | 0x08888888u) + 1u) & 0xf7777777u; } -uint rosc_find_freq(uint32_t low_mhz, uint32_t high_mhz) { +uint rosc_find_freq(uint32_t low_mhz, uint32_t high_mhz) +{ // TODO: This could be a lot better rosc_set_div(1); for (uint32_t code = 0; code <= 0x77777777u; code = next_rosc_code(code)) { @@ -29,33 +31,40 @@ uint rosc_find_freq(uint32_t low_mhz, uint32_t high_mhz) { return 0; } -void rosc_set_div(uint32_t div) { +void rosc_set_div(uint32_t div) +{ assert(div <= 31 && div >= 1); rosc_write(&rosc_hw->div, ROSC_DIV_VALUE_PASS + div); } -void rosc_set_freq(uint32_t code) { +void rosc_set_freq(uint32_t code) +{ rosc_write(&rosc_hw->freqa, (ROSC_FREQA_PASSWD_VALUE_PASS << ROSC_FREQA_PASSWD_LSB) | (code & 0xffffu)); rosc_write(&rosc_hw->freqb, (ROSC_FREQA_PASSWD_VALUE_PASS << ROSC_FREQA_PASSWD_LSB) | (code >> 16u)); } -void rosc_set_range(uint range) { +void rosc_set_range(uint range) +{ // Range should use enumvals from the headers and thus have the password correct rosc_write(&rosc_hw->ctrl, (ROSC_CTRL_ENABLE_VALUE_ENABLE << ROSC_CTRL_ENABLE_LSB) | range); } -void rosc_disable(void) { +void rosc_disable(void) +{ uint32_t tmp = rosc_hw->ctrl; tmp &= (~ROSC_CTRL_ENABLE_BITS); tmp |= (ROSC_CTRL_ENABLE_VALUE_DISABLE << ROSC_CTRL_ENABLE_LSB); rosc_write(&rosc_hw->ctrl, tmp); // Wait for stable to go away - while(rosc_hw->status & ROSC_STATUS_STABLE_BITS); + while (rosc_hw->status & ROSC_STATUS_STABLE_BITS) + ; } -void rosc_set_dormant(void) { +void rosc_set_dormant(void) +{ // WARNING: This stops the rosc until woken up by an irq rosc_write(&rosc_hw->dormant, ROSC_DORMANT_VALUE_DORMANT); // Wait for it to become stable once woken up - while(!(rosc_hw->status & ROSC_STATUS_STABLE_BITS)); + while (!(rosc_hw->status & ROSC_STATUS_STABLE_BITS)) + ; } \ No newline at end of file diff --git a/src/platform/rp2xx0/main-rp2xx0.cpp b/src/platform/rp2xx0/main-rp2xx0.cpp index 60847f318..67bf1eb08 100644 --- a/src/platform/rp2xx0/main-rp2xx0.cpp +++ b/src/platform/rp2xx0/main-rp2xx0.cpp @@ -2,9 +2,9 @@ #include "hardware/xosc.h" #include #include +#include #include #include -#include void setBluetoothEnable(bool enable) { @@ -13,11 +13,13 @@ void setBluetoothEnable(bool enable) static bool awake; -static void sleep_callback(void) { +static void sleep_callback(void) +{ awake = true; } -void epoch_to_datetime(time_t epoch, datetime_t *dt) { +void epoch_to_datetime(time_t epoch, datetime_t *dt) +{ struct tm *tm_info; tm_info = gmtime(&epoch); @@ -39,7 +41,7 @@ void debug_date(datetime_t t) void cpuDeepSleep(uint32_t msecs) { - time_t seconds = (time_t)(msecs/1000); + time_t seconds = (time_t)(msecs / 1000); datetime_t t_init, t_alarm; awake = false; @@ -54,7 +56,7 @@ void cpuDeepSleep(uint32_t msecs) sleep_run_from_dormant_source(DORMANT_SOURCE_ROSC); sleep_goto_sleep_until(&t_alarm, &sleep_callback); - // Make sure we don't wake + // Make sure we don't wake while (!awake) { delay(1); } diff --git a/src/platform/rp2xx0/pico_sleep/include/pico/sleep.h b/src/platform/rp2xx0/pico_sleep/include/pico/sleep.h index b97a23169..17dff2468 100644 --- a/src/platform/rp2xx0/pico_sleep/include/pico/sleep.h +++ b/src/platform/rp2xx0/pico_sleep/include/pico/sleep.h @@ -7,8 +7,8 @@ #ifndef _PICO_SLEEP_H_ #define _PICO_SLEEP_H_ -#include "pico.h" #include "hardware/rtc.h" +#include "pico.h" #ifdef __cplusplus extern "C" { @@ -30,11 +30,7 @@ extern "C" { * \include hello_sleep.c */ -typedef enum { - DORMANT_SOURCE_NONE, - DORMANT_SOURCE_XOSC, - DORMANT_SOURCE_ROSC -} dormant_source_t; +typedef enum { DORMANT_SOURCE_NONE, DORMANT_SOURCE_XOSC, DORMANT_SOURCE_ROSC } dormant_source_t; /*! \brief Set all clock sources to the the dormant clock source to prepare for sleep. * \ingroup hardware_sleep @@ -46,14 +42,16 @@ void sleep_run_from_dormant_source(dormant_source_t dormant_source); /*! \brief Set the dormant clock source to be the crystal oscillator * \ingroup hardware_sleep */ -static inline void sleep_run_from_xosc(void) { +static inline void sleep_run_from_xosc(void) +{ sleep_run_from_dormant_source(DORMANT_SOURCE_XOSC); } /*! \brief Set the dormant clock source to be the ring oscillator * \ingroup hardware_sleep */ -static inline void sleep_run_from_rosc(void) { +static inline void sleep_run_from_rosc(void) +{ sleep_run_from_dormant_source(DORMANT_SOURCE_ROSC); } @@ -85,7 +83,8 @@ void sleep_goto_dormant_until_pin(uint gpio_pin, bool edge, bool high); * * \param gpio_pin The pin to provide the wake up */ -static inline void sleep_goto_dormant_until_edge_high(uint gpio_pin) { +static inline void sleep_goto_dormant_until_edge_high(uint gpio_pin) +{ sleep_goto_dormant_until_pin(gpio_pin, true, true); } @@ -96,7 +95,8 @@ static inline void sleep_goto_dormant_until_edge_high(uint gpio_pin) { * * \param gpio_pin The pin to provide the wake up */ -static inline void sleep_goto_dormant_until_level_high(uint gpio_pin) { +static inline void sleep_goto_dormant_until_level_high(uint gpio_pin) +{ sleep_goto_dormant_until_pin(gpio_pin, false, true); } diff --git a/src/platform/rp2xx0/pico_sleep/sleep.c b/src/platform/rp2xx0/pico_sleep/sleep.c index 1bb8db699..65096be85 100644 --- a/src/platform/rp2xx0/pico_sleep/sleep.c +++ b/src/platform/rp2xx0/pico_sleep/sleep.c @@ -6,22 +6,22 @@ #include "pico.h" -#include "pico/stdlib.h" #include "pico/sleep.h" +#include "pico/stdlib.h" -#include "hardware/rtc.h" -#include "hardware/pll.h" #include "hardware/clocks.h" -#include "hardware/xosc.h" -#include "hardware/rosc.h" +#include "hardware/pll.h" #include "hardware/regs/io_bank0.h" +#include "hardware/rosc.h" +#include "hardware/rtc.h" +#include "hardware/xosc.h" // For __wfi #include "hardware/sync.h" // For scb_hw so we can enable deep sleep #include "hardware/structs/scb.h" // when using old SDK this macro is not defined #ifndef XOSC_HZ - #define XOSC_HZ 12000000u +#define XOSC_HZ 12000000u #endif // The difference between sleep and dormant is that ALL clocks are stopped in dormant mode, // until the source (either xosc or rosc) is started again by an external event. @@ -29,41 +29,37 @@ // block. For example you could keep clk_rtc running. Some destinations (proc0 and proc1 wakeup logic) // can't be stopped in sleep mode otherwise there wouldn't be enough logic to wake up again. - // TODO: Optionally, memories can also be powered down. static dormant_source_t _dormant_source; -bool dormant_source_valid(dormant_source_t dormant_source) { +bool dormant_source_valid(dormant_source_t dormant_source) +{ return (dormant_source == DORMANT_SOURCE_XOSC) || (dormant_source == DORMANT_SOURCE_ROSC); } // In order to go into dormant mode we need to be running from a stoppable clock source: // either the xosc or rosc with no PLLs running. This means we disable the USB and ADC clocks // and all PLLs -void sleep_run_from_dormant_source(dormant_source_t dormant_source) { +void sleep_run_from_dormant_source(dormant_source_t dormant_source) +{ assert(dormant_source_valid(dormant_source)); _dormant_source = dormant_source; // FIXME: Just defining average rosc freq here. uint src_hz = (dormant_source == DORMANT_SOURCE_XOSC) ? XOSC_HZ : 6.5 * MHZ; - uint clk_ref_src = (dormant_source == DORMANT_SOURCE_XOSC) ? - CLOCKS_CLK_REF_CTRL_SRC_VALUE_XOSC_CLKSRC : - CLOCKS_CLK_REF_CTRL_SRC_VALUE_ROSC_CLKSRC_PH; + uint clk_ref_src = (dormant_source == DORMANT_SOURCE_XOSC) ? CLOCKS_CLK_REF_CTRL_SRC_VALUE_XOSC_CLKSRC + : CLOCKS_CLK_REF_CTRL_SRC_VALUE_ROSC_CLKSRC_PH; // CLK_REF = XOSC or ROSC - clock_configure(clk_ref, - clk_ref_src, + clock_configure(clk_ref, clk_ref_src, 0, // No aux mux - src_hz, - src_hz); + src_hz, src_hz); // CLK SYS = CLK_REF - clock_configure(clk_sys, - CLOCKS_CLK_SYS_CTRL_SRC_VALUE_CLK_REF, + clock_configure(clk_sys, CLOCKS_CLK_SYS_CTRL_SRC_VALUE_CLK_REF, 0, // Using glitchless mux - src_hz, - src_hz); + src_hz, src_hz); // CLK USB = 0MHz clock_stop(clk_usb); @@ -72,22 +68,15 @@ void sleep_run_from_dormant_source(dormant_source_t dormant_source) { clock_stop(clk_adc); // CLK RTC = ideally XOSC (12MHz) / 256 = 46875Hz but could be rosc - uint clk_rtc_src = (dormant_source == DORMANT_SOURCE_XOSC) ? - CLOCKS_CLK_RTC_CTRL_AUXSRC_VALUE_XOSC_CLKSRC : - CLOCKS_CLK_RTC_CTRL_AUXSRC_VALUE_ROSC_CLKSRC_PH; + uint clk_rtc_src = (dormant_source == DORMANT_SOURCE_XOSC) ? CLOCKS_CLK_RTC_CTRL_AUXSRC_VALUE_XOSC_CLKSRC + : CLOCKS_CLK_RTC_CTRL_AUXSRC_VALUE_ROSC_CLKSRC_PH; clock_configure(clk_rtc, 0, // No GLMUX - clk_rtc_src, - src_hz, - 46875); + clk_rtc_src, src_hz, 46875); // CLK PERI = clk_sys. Used as reference clock for Peripherals. No dividers so just select and enable - clock_configure(clk_peri, - 0, - CLOCKS_CLK_PERI_CTRL_AUXSRC_VALUE_CLK_SYS, - src_hz, - src_hz); + clock_configure(clk_peri, 0, CLOCKS_CLK_PERI_CTRL_AUXSRC_VALUE_CLK_SYS, src_hz, src_hz); pll_deinit(pll_sys); pll_deinit(pll_usb); @@ -103,11 +92,12 @@ void sleep_run_from_dormant_source(dormant_source_t dormant_source) { // Reconfigure uart with new clocks /* This dones not work with our current core */ - //setup_default_uart(); + // setup_default_uart(); } // Go to sleep until woken up by the RTC -void sleep_goto_sleep_until(datetime_t *t, rtc_callback_t callback) { +void sleep_goto_sleep_until(datetime_t *t, rtc_callback_t callback) +{ // We should have already called the sleep_run_from_dormant_source function assert(dormant_source_valid(_dormant_source)); @@ -125,7 +115,8 @@ void sleep_goto_sleep_until(datetime_t *t, rtc_callback_t callback) { __wfi(); } -static void _go_dormant(void) { +static void _go_dormant(void) +{ assert(dormant_source_valid(_dormant_source)); if (_dormant_source == DORMANT_SOURCE_XOSC) { @@ -135,7 +126,8 @@ static void _go_dormant(void) { } } -void sleep_goto_dormant_until_pin(uint gpio_pin, bool edge, bool high) { +void sleep_goto_dormant_until_pin(uint gpio_pin, bool edge, bool high) +{ bool low = !high; bool level = !edge; @@ -144,10 +136,14 @@ void sleep_goto_dormant_until_pin(uint gpio_pin, bool edge, bool high) { uint32_t event = 0; - if (level && low) event = IO_BANK0_DORMANT_WAKE_INTE0_GPIO0_LEVEL_LOW_BITS; - if (level && high) event = IO_BANK0_DORMANT_WAKE_INTE0_GPIO0_LEVEL_HIGH_BITS; - if (edge && high) event = IO_BANK0_DORMANT_WAKE_INTE0_GPIO0_EDGE_HIGH_BITS; - if (edge && low) event = IO_BANK0_DORMANT_WAKE_INTE0_GPIO0_EDGE_LOW_BITS; + if (level && low) + event = IO_BANK0_DORMANT_WAKE_INTE0_GPIO0_LEVEL_LOW_BITS; + if (level && high) + event = IO_BANK0_DORMANT_WAKE_INTE0_GPIO0_LEVEL_HIGH_BITS; + if (edge && high) + event = IO_BANK0_DORMANT_WAKE_INTE0_GPIO0_EDGE_HIGH_BITS; + if (edge && low) + event = IO_BANK0_DORMANT_WAKE_INTE0_GPIO0_EDGE_LOW_BITS; gpio_set_dormant_irq_enabled(gpio_pin, event, true); From 876993f0957c9d1b721dd8d09692b45b61d9bf10 Mon Sep 17 00:00:00 2001 From: Ben Meadors Date: Tue, 8 Oct 2024 05:34:41 -0500 Subject: [PATCH 87/88] No idea why trunk wants to disturb these PNGs but... --- images/compass.png | Bin 845 -> 594 bytes images/face-24px.svg | 2 +- images/face.png | Bin 329 -> 225 bytes images/location_searching-24px.svg | 2 +- images/pin.png | Bin 288 -> 203 bytes images/room-24px.svg | 2 +- images/textsms-24px.svg | 2 +- 7 files changed, 4 insertions(+), 4 deletions(-) diff --git a/images/compass.png b/images/compass.png index 8639dde5241d720e47e97d63280ec8073928c2b4..c4e5b589bc42cd7b05148dbbdee01ce0fe689548 100644 GIT binary patch delta 561 zcmV-10?z%-2GRtO83+Ub008|9F$|G07k>f-NklyvaQ|Snd!k0 z`OI;De`Ye9Uv~M=M1R(0gMZLqh6X-u)u4?}gX=K75ti8{AR4f`yk!Xo>{a+clz*{~ zS-?t;4MHM~72@M!Xo7>D5=T6yMwv0j@Tjp$r>9Aaf?4_RvEr{NF-VEc*cngsTjXN9 zKczyNS{PNkjF4(sU2O#u zRdw#WqqAXKWlx_6mt!NXR2>tYyBeY9QCJ zQCGwKFHzsRiH&l9o#Y02Y~=MDT*1aw{RSm$c>Q&fFZs?;mwZSfUqV)~@l>*(k*J|Y zmW{8HeV;@#bY)bOt#9BLQ>56HuuV+8k<4vUEva!mi-~zPt`|w=@KFNKxqpVPB0nVS z2!{-FYA^e^=*aP2G6HU+!6%Y+K#?qys(i#cT3lKx<%}w6<~difdyJx~z==u=*`mxK z9i+&9KCP@vWKiMvJ}k34xi>OA2~&+|RTG33(J{P+!6XA~>9XlIu1FbDP=?y*BR z;Rj@!MI0F3G%GY?r#a*~4<4AhKtF+(4KB3b>M76a97!*<00000NkvXXu0mjfa`FP& delta 814 zcmV+}1JV4_1kDDJ85jlt00374`G)`i00eVFNmK|32nc)#WQdU=7k>a5bVXQnQ*UN; zcVTj60C#tHE@^ISb7Ns}WiD@WXPfRk8UO$S%1J~)RA_# zlVG9=+yX8ERp5{xHUHjipp{U_HZYT?`L8j?9|8**v=)F3qJMjFj~t4aCi=;L!@LW& zoCWqHbhl9+PU|sA$_m;QU?)QVzJfMjW(e8U+E1uRxQDyIqN{KL_$Y*b0JE;b5tK1Q zGMKA{`PNvoDg-^;#{4iA3HSCj7r~c8?17`fG&~YHpW6x@XK;Dok!`B9rN&?{bbvV< zp_>doiBC!f(|^zwxo^ZZOj=0E73EWRU#XF~>TwN|3OFgQ-&@?49B(<+B1st_7V#~3#4TA+tiP#lwt>$7&WC0Dr z{($5jXp8F$D%R3*QCv6U8fGcrs9sJi(|MUBDP<_{U(3CX4q z+fXn#j3*-JGZ(QHA?9JWfqAh+csaf7B3J-E2*IDg5ht6`RDkayR}+PUuXBW-$_~0) z%4y)O$k7GPXeC$^;yuhBwxXatOW1r5xTm1~k0NFxFO%%!w((xV3`wcGh3>&KU=Ex1 zB9eKSZGT{vDYgbYCi-CO3vgJ?wP1$mp6Ev#xC31FO_uzq`So0&Q1-? s({2H;f!`WQC;t \ No newline at end of file + \ No newline at end of file diff --git a/images/face.png b/images/face.png index 036e29f7349217607c53f48aed28e99484a3e648..eb6b91e13b89f3a0d27efbaf83e35f2c1f70b3c5 100644 GIT binary patch delta 188 zcmV;t07L)D0^tFW83+Ub007wHEccNy7=M#VL_t(|+J(?P4gpaVhT*4BON@<(8woX? zLS_XDt%M~QvlYFcZ7@+#}B!d5~QJk`Ieg!u6Zu6ANf zfL!gRuO;*HjTun5835X*7IGKhu7|lHM&<}gpfJPQ7!xa`&cN2*zmpA+s4PV*4=Ejh qpmLB3Qb!McqD1DRbhgoH-0ltI05a+a8KhYN0000MzCV_|S*E^l&Yo9;Xs0002SNkl|LzC>pdL!hvB*6^ z(FP3ghR+|)I{B>%HGlAmX$!bfu}tCvee7YJxCxG7C(s-nTw~VwY#*06!YQtBUMH70 zi@(7|{4jAn^8$AB@Q#!CLv-W2IEX*a+~1nu!S8y;ee \ No newline at end of file + \ No newline at end of file diff --git a/images/pin.png b/images/pin.png index 112a7ce8ed6a7537c73dc2626d2f6cab93d87fbc..3c91a726c3cf3c5605e1580a89e35f84850da2f6 100644 GIT binary patch delta 166 zcmV;X09pT_0?PrA83+Ub007wHEccNy7=L|9L_t(|+KtdL4#5BzhT&&nDRCHfEL=e( zB;q9E1TG-%!VTP@Sj56g`b(r~qv_D+8{h5I#MH^f(L}{sCVtDTDD}LA)J`fqbrr@! z7-A%Zk-|U-3oM1uS7>_(Z)YFju0?4pif#PqxaHw0Q8CZcOpSxES1YlXGMzCV_|S*E^l&Yo9;Xs0001;Nkl# BWEB7a diff --git a/images/room-24px.svg b/images/room-24px.svg index 79a4807e7..48e55ab80 100644 --- a/images/room-24px.svg +++ b/images/room-24px.svg @@ -1 +1 @@ - \ No newline at end of file + \ No newline at end of file diff --git a/images/textsms-24px.svg b/images/textsms-24px.svg index 4455f047e..84c4fdcc1 100644 --- a/images/textsms-24px.svg +++ b/images/textsms-24px.svg @@ -1 +1 @@ - \ No newline at end of file + \ No newline at end of file From 4f8f96ab2967660e03e7a9ef9beef633c60ddac6 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Thomas=20G=C3=B6ttgens?= Date: Tue, 8 Oct 2024 14:05:13 +0200 Subject: [PATCH 88/88] preliminary Othernet Dreamcatcher Support (#4933) * preliminary Othernet Dreamcatcher 2206 Support Need to adapt to 2301 final version * second target for latest revision * preliminary Othernet Dreamcatcher 2206 Support Need to adapt to 2301 final version * second target for latest revision * preliminary Othernet Dreamcatcher 2206 Support Need to adapt to 2301 final version * second target for latest revision * address comments --------- Co-authored-by: Ben Meadors Co-authored-by: Tom Fifield --- src/configuration.h | 5 ++ src/detect/ScanI2C.h | 3 +- src/detect/ScanI2CTwoWire.cpp | 3 + src/main.cpp | 20 +++++ src/mesh/LR11x0Interface.cpp | 12 +++ variants/dreamcatcher/platformio.ini | 27 +++++++ variants/dreamcatcher/rfswitch.h | 17 +++++ variants/dreamcatcher/variant.h | 109 +++++++++++++++++++++++++++ 8 files changed, 195 insertions(+), 1 deletion(-) create mode 100644 variants/dreamcatcher/platformio.ini create mode 100644 variants/dreamcatcher/rfswitch.h create mode 100644 variants/dreamcatcher/variant.h diff --git a/src/configuration.h b/src/configuration.h index 729d6b046..10a4e0a99 100644 --- a/src/configuration.h +++ b/src/configuration.h @@ -187,6 +187,11 @@ along with this program. If not, see . // ----------------------------------------------------------------------------- #define FT6336U_ADDR 0x48 +// ----------------------------------------------------------------------------- +// BIAS-T Generator +// ----------------------------------------------------------------------------- +#define TPS65233_ADDR 0x60 + // convert 24-bit color to 16-bit (56K) #define COLOR565(r, g, b) (((r & 0xF8) << 8) | ((g & 0xFC) << 3) | ((b & 0xF8) >> 3)) diff --git a/src/detect/ScanI2C.h b/src/detect/ScanI2C.h index 920af06c7..07db3fd57 100644 --- a/src/detect/ScanI2C.h +++ b/src/detect/ScanI2C.h @@ -60,7 +60,8 @@ class ScanI2C FT6336U, STK8BAXX, ICM20948, - MAX30102 + MAX30102, + TPS65233 } DeviceType; // typedef uint8_t DeviceAddress; diff --git a/src/detect/ScanI2CTwoWire.cpp b/src/detect/ScanI2CTwoWire.cpp index 3f4f88f74..af94290d2 100644 --- a/src/detect/ScanI2CTwoWire.cpp +++ b/src/detect/ScanI2CTwoWire.cpp @@ -405,6 +405,9 @@ void ScanI2CTwoWire::scanPort(I2CPort port, uint8_t *address, uint8_t asize) SCAN_SIMPLE_CASE(NAU7802_ADDR, NAU7802, "NAU7802 based scale found\n"); SCAN_SIMPLE_CASE(FT6336U_ADDR, FT6336U, "FT6336U touchscreen found\n"); SCAN_SIMPLE_CASE(MAX1704X_ADDR, MAX17048, "MAX17048 lipo fuel gauge found\n"); +#ifdef HAS_TPS65233 + SCAN_SIMPLE_CASE(TPS65233_ADDR, TPS65233, "TPS65233 BIAS-T found\n"); +#endif SCAN_SIMPLE_CASE(MLX90614_ADDR_DEF, MLX90614, "MLX90614 IR temp sensor found\n"); case ICM20948_ADDR: // same as BMX160_ADDR diff --git a/src/main.cpp b/src/main.cpp index 9ddc0864c..8387392fe 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -298,6 +298,11 @@ void setup() digitalWrite(VEXT_ENABLE, VEXT_ON_VALUE); // turn on the display power #endif +#if defined(BIAS_T_ENABLE) + pinMode(BIAS_T_ENABLE, OUTPUT); + digitalWrite(BIAS_T_ENABLE, BIAS_T_VALUE); // turn on 5V for GPS Antenna +#endif + #if defined(VTFT_CTRL) pinMode(VTFT_CTRL, OUTPUT); digitalWrite(VTFT_CTRL, LOW); @@ -538,6 +543,21 @@ void setup() rgb_found = i2cScanner->find(ScanI2C::DeviceType::NCP5623); #endif +#ifdef HAS_TPS65233 + // TPS65233 is a power management IC for satellite modems, used in the Dreamcatcher + // We are switching it off here since we don't use an LNB. + if (i2cScanner->exists(ScanI2C::DeviceType::TPS65233)) { + Wire.beginTransmission(TPS65233_ADDR); + Wire.write(0); // Register 0 + Wire.write(128); // Turn off the LNB power, keep I2C Control enabled + Wire.endTransmission(); + Wire.beginTransmission(TPS65233_ADDR); + Wire.write(1); // Register 1 + Wire.write(0); // Turn off Tone Generator 22kHz + Wire.endTransmission(); + } +#endif + #if !defined(ARCH_PORTDUINO) && !defined(ARCH_STM32WL) auto acc_info = i2cScanner->firstAccelerometer(); accelerometer_found = acc_info.type != ScanI2C::DeviceType::NONE ? acc_info.address : accelerometer_found; diff --git a/src/mesh/LR11x0Interface.cpp b/src/mesh/LR11x0Interface.cpp index 6641634c4..a985a9006 100644 --- a/src/mesh/LR11x0Interface.cpp +++ b/src/mesh/LR11x0Interface.cpp @@ -72,6 +72,18 @@ template bool LR11x0Interface::init() limitPower(); +#ifdef LR11X0_RF_SWITCH_SUBGHZ + pinMode(LR11X0_RF_SWITCH_SUBGHZ, OUTPUT); + digitalWrite(LR11X0_RF_SWITCH_SUBGHZ, getFreq() < 1e9 ? HIGH : LOW); + LOG_DEBUG("Setting RF0 switch to %s\n", getFreq() < 1e9 ? "SubGHz" : "2.4GHz"); +#endif + +#ifdef LR11X0_RF_SWITCH_2_4GHZ + pinMode(LR11X0_RF_SWITCH_2_4GHZ, OUTPUT); + digitalWrite(LR11X0_RF_SWITCH_2_4GHZ, getFreq() < 1e9 ? LOW : HIGH); + LOG_DEBUG("Setting RF1 switch to %s\n", getFreq() < 1e9 ? "SubGHz" : "2.4GHz"); +#endif + int res = lora.begin(getFreq(), bw, sf, cr, syncWord, power, preambleLength, tcxoVoltage); // \todo Display actual typename of the adapter, not just `LR11x0` LOG_INFO("LR11x0 init result %d\n", res); diff --git a/variants/dreamcatcher/platformio.ini b/variants/dreamcatcher/platformio.ini new file mode 100644 index 000000000..46f9b9871 --- /dev/null +++ b/variants/dreamcatcher/platformio.ini @@ -0,0 +1,27 @@ +[env:dreamcatcher] ; 2301, latest revision +extends = esp32s3_base +board = esp32s3box +board_level = extra + +build_flags = + ${esp32s3_base.build_flags} + -D PRIVATE_HW + -D OTHERNET_DC_REV=2301 + -I variants/dreamcatcher + -DARDUINO_USB_CDC_ON_BOOT=1 + +lib_deps = ${esp32s3_base.lib_deps} + earlephilhower/ESP8266Audio@^1.9.7 + earlephilhower/ESP8266SAM@^1.0.1 + +[env:dreamcatcher-2206] +extends = esp32s3_base +board = esp32s3box +board_level = extra + +build_flags = + ${esp32s3_base.build_flags} + -D PRIVATE_HW + -D OTHERNET_DC_REV=2206 + -I variants/dreamcatcher + -DARDUINO_USB_CDC_ON_BOOT=1 \ No newline at end of file diff --git a/variants/dreamcatcher/rfswitch.h b/variants/dreamcatcher/rfswitch.h new file mode 100644 index 000000000..74edb25d1 --- /dev/null +++ b/variants/dreamcatcher/rfswitch.h @@ -0,0 +1,17 @@ +#include "RadioLib.h" + +// RF Switch Matrix SubG RFO_HP_LF / RFO_LP_LF / RFI_[NP]_LF0 +// DIO5 -> RFSW0_V1 +// DIO6 -> RFSW1_V2 +// DIO7 -> ANT_CTRL_ON + ESP_IO9/LR_GPS_ANT_DC_EN -> RFI_GPS (Bias-T GPS) + +static const uint32_t rfswitch_dio_pins[] = {RADIOLIB_LR11X0_DIO5, RADIOLIB_LR11X0_DIO6, RADIOLIB_LR11X0_DIO7, RADIOLIB_NC, + RADIOLIB_NC}; + +static const Module::RfSwitchMode_t rfswitch_table[] = { + // mode DIO5 DIO6 DIO7 + {LR11x0::MODE_STBY, {LOW, LOW, LOW}}, {LR11x0::MODE_RX, {HIGH, LOW, LOW}}, + {LR11x0::MODE_TX, {LOW, HIGH, LOW}}, {LR11x0::MODE_TX_HP, {LOW, HIGH, LOW}}, + {LR11x0::MODE_TX_HF, {LOW, LOW, LOW}}, {LR11x0::MODE_GNSS, {LOW, LOW, HIGH}}, + {LR11x0::MODE_WIFI, {LOW, LOW, LOW}}, END_OF_MODE_TABLE, +}; \ No newline at end of file diff --git a/variants/dreamcatcher/variant.h b/variants/dreamcatcher/variant.h new file mode 100644 index 000000000..eb95a95dd --- /dev/null +++ b/variants/dreamcatcher/variant.h @@ -0,0 +1,109 @@ +#undef I2C_SDA +#undef I2C_SCL +#define I2C_SDA 16 // I2C pins for this board +#define I2C_SCL 17 + +#define I2C_SDA1 45 +#define I2C_SCL1 46 + +#define LED_PIN 6 +#define LED_STATE_ON 1 +#define BUTTON_PIN 0 + +#define HAS_TPS65233 + +// V1 of SubG Switch SMA 0 or F Selector 1 +// #define RF_SW_SUBG1 8 +// V2 of SubG Switch SMA 1 or F Selector 0 +// #define RF_SW_SUBG2 5 + +#define RESET_OLED 8 // Emulate RF_SW_SUBG1, Use F Connector +#define VTFT_CTRL 5 // Emulate RF_SW_SUBG2, for SMA swap the pin values + +#if OTHERNET_DC_REV == 2206 +#define USE_LR1120 + +#define SPI_MISO 37 +#define SPI_MOSI 39 +#define SPI_SCK 38 +#define SDCARD_CS 40 + +#define PIN_BUZZER 48 + +// These can either be used for GPS or a serial link. Define through Protobufs +// #define GPS_RX_PIN 10 +// #define GPS_TX_PIN 21 + +#define PIN_POWER_EN 7 // RF section power supply enable +#define PERIPHERAL_WARMUP_MS 1000 // wait for TPS chip to initialize +#define TPS_EXTM 45 // connected, but not used +#define BIAS_T_ENABLE 9 // needs to be low +#define BIAS_T_VALUE 0 +#else // 2301 +#define USE_LR1121 +#define SPI_MISO 10 +#define SPI_MOSI 39 +#define SPI_SCK 38 + +#define SDCARD_CS 40 + +// This is only informational, we always use SD cards in 1 bit mode +#define SPI_DATA1 15 +#define SPI_DATA2 18 + +// These can either be used for GPS or a serial link. Define through Protobufs +// #define GPS_RX_PIN 36 +// #define GPS_TX_PIN 37 + +// dac / amp instead of buzzer +#define HAS_I2S +#define DAC_I2S_BCK 21 +#define DAC_I2S_WS 9 +#define DAC_I2S_DOUT 48 + +#define BIAS_T_ENABLE 7 // needs to be low +#define BIAS_T_VALUE 0 +#define BIAS_T_SUBGHZ 2 // also needs to be low, we hijack SENSOR_POWER_CTRL_PIN to emulate this +#define SENSOR_POWER_CTRL_PIN BIAS_T_SUBGHZ +#define SENSOR_POWER_ON 0 +#endif + +#define HAS_SDCARD // Have SPI interface SD card slot +#define SDCARD_USE_SPI1 + +#define LORA_RESET 3 +#define LORA_SCK 12 +#define LORA_MISO 13 +#define LORA_MOSI 11 +#define LORA_CS 14 +#define LORA_DIO9 4 +#define LORA_DIO2 47 + +#define LR1120_IRQ_PIN LORA_DIO9 +#define LR1120_NRESET_PIN LORA_RESET +#define LR1120_BUSY_PIN LORA_DIO2 +#define LR1120_SPI_NSS_PIN LORA_CS +#define LR1120_SPI_SCK_PIN LORA_SCK +#define LR1120_SPI_MOSI_PIN LORA_MOSI +#define LR1120_SPI_MISO_PIN LORA_MISO + +#define LR1121_IRQ_PIN LORA_DIO9 +#define LR1121_NRESET_PIN LORA_RESET +#define LR1121_BUSY_PIN LORA_DIO2 +#define LR1121_SPI_NSS_PIN LORA_CS +#define LR1121_SPI_SCK_PIN LORA_SCK +#define LR1121_SPI_MOSI_PIN LORA_MOSI +#define LR1121_SPI_MISO_PIN LORA_MISO + +#define LR11X0_DIO3_TCXO_VOLTAGE 1.8 +#define LR11X0_DIO_AS_RF_SWITCH + +// This board needs external switching between sub-GHz and 2.4G circuits + +// V1 of RF1 selector SubG 1 or 2.4GHz 0 +// #define RF_SW_SMA1 42 +// V2 of RF1 Selector SubG 0 or 2.4GHz 1 +// #define RF_SW_SMA2 41 + +#define LR11X0_RF_SWITCH_SUBGHZ 42 +#define LR11X0_RF_SWITCH_2_4GHZ 41