From 6d00ee327f52271a0b63f9afe5d5aaa5b9847532 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?J=C3=B6rg=20Ebeling?= Date: Mon, 7 Oct 2024 23:43:24 +0200 Subject: [PATCH 01/32] Initial proposal --- Firmware/LowLevel/include/nv_config.h | 84 +++++++++++++++++++++++++++ Firmware/LowLevel/src/datatypes.h | 31 +++++++++- Firmware/LowLevel/src/main.cpp | 61 +++++++++++++++---- 3 files changed, 164 insertions(+), 12 deletions(-) create mode 100644 Firmware/LowLevel/include/nv_config.h diff --git a/Firmware/LowLevel/include/nv_config.h b/Firmware/LowLevel/include/nv_config.h new file mode 100644 index 00000000..4a8f57c1 --- /dev/null +++ b/Firmware/LowLevel/include/nv_config.h @@ -0,0 +1,84 @@ +/* + * Copyright 2024 Jörg Ebeling (Apehaenger) + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in all + * copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE.* Testing/examples for reading/writing flash on the RP2040. + * + * Heavily inspired, copied from, as well as must-read: + * https://github.com/MakerMatrix/RP2040_flash_programming + */ + +#ifndef _NV_CONFIG_H +#define _NV_CONFIG_H + +#include + +#ifdef ENABLE_SOUND_MODULE +#include "soundsystem.h" +#else +#define VOLUME_DEFAULT 80 +#endif + +#define VOLUME_DEFAULT 80 // FIXME: Backported from PR-80 + +#include "../src/datatypes.h" + +#define NV_CONFIG_MAX_SAVE_INTERVAL 60000UL // Don't save more often than once a minute + +// config_bitmask. Don't mistake with LL_HIGH_LEVEL_CONFIG_BIT. Similar, but not mandatory equal! +#define NV_CONFIG_BIT_DFPIS5V 1 << 0 // DFP is set to 5V + +#define NV_RECORD_ID 0x4F4D4331 // Record struct identifier "OMC1" for future flexible length Record.config +#define NV_RECORD_ALIGNMENT (_Alignof(uint32_t)) // Ptr alignment of Record.id for quick in memory access + +namespace nv_config { +#pragma pack(push, 1) +// This is where our application values should go. +// It's possible to extended it, but any extension should add an extension related CRC so that an old/last stored Record.config isn't lost. +// (a new extension-crc isn't valid with a old Record.config. Thus the new extension values may get set i.e. with default values) +struct Config { + // Config bitmask: + // Bit 0: DFP is 5V (enable full sound). See NV_CONFIG_BIT_DFPIS5V + uint8_t config_bitmask = 0; // Don't mistake with LL_HIGH_LEVEL_CONFIG_BIT. Similar, but not mandatory equal! + uint8_t volume = VOLUME_DEFAULT; // Sound volume (0-100%) + iso639_1 language = {'e', 'n'}; // Default to 'en' + uint32_t rain_threshold = 700; // If (stock CoverUI) rain value < rain_threshold then it rains. Expected to differ between C500, SA and SC types + + /* Possible future config settings + uint16_t free; // Future config setting + uint16_t free_n; // Future config setting + uint16_t crc_n; // Future config CRC16 (for the new member) for detection if loaded (possibly old) config already has the new member */ +} __attribute__((packed)); + +// Record(s) get placed sequentially into a flash page. +// The Record structure shouldn't get changed, because it would make old flash Record's unusable. Instead of, change Record.config +struct Record { + const uint32_t id = NV_RECORD_ID; // Fixed record identifier, used to identify a possible Record within a flash page. If width get changed, change also NV_RECORD_ALIGNMENT + uint32_t num_sector_erase = 0; // For wear level stats + uint32_t num_page_write = 0; // For informational purposes + uint16_t crc; // Required to ensure that a found NV_RECORD_ID is really a Record + Config config; +} __attribute__((packed)); +#pragma pack(pop) + +Config *get(); // Returned Config pointer hold the data of the last saved Record.config, or a default one. Config member are writable, see delayedSaveChanges() +void delayedSaveChanges(); // Handle a possible changed nv_config::config member and save it to flash, but only within NV_CONFIG_MAX_SAVE_INTERVAL timeout for wear level protection + +} // namespace nv_config + +#endif // _NV_CONFIG_H \ No newline at end of file diff --git a/Firmware/LowLevel/src/datatypes.h b/Firmware/LowLevel/src/datatypes.h index 7f3dd9ca..cbc1a39b 100644 --- a/Firmware/LowLevel/src/datatypes.h +++ b/Firmware/LowLevel/src/datatypes.h @@ -60,7 +60,7 @@ struct ll_status { // Bit 0: Initialized (i.e. setup() was a success). If this is 0, all other bits are meaningless. // Bit 1: Raspberry Power // Bit 2: Charging enabled - // Bit 3: don't care + // Bit 3: don't care (reserved for ESC shutdown PR) // Bit 4: Rain detected // Bit 5: Sound available // Bit 6: Sound busy @@ -74,6 +74,7 @@ struct ll_status { // Bit 2: Emergency/Hall 4 (Stop2) active // Bit 3: Emergency/Hall 1 (Lift1) active // Bit 4: Emergency/Hall 2 (Lift2) active + // Bit 5: Not an emergency but probably usable for pause via SA Handle? uint8_t emergency_bitmask; // Charge voltage float v_charge; @@ -135,12 +136,22 @@ struct ll_ui_event { } __attribute__((packed)); #pragma pack(pop) -#define LL_HIGH_LEVEL_CONFIG_MAX_COMMS_VERSION 1 // Max. comms packet version supported by this open_mower LL FW +#define LL_HIGH_LEVEL_CONFIG_MAX_COMMS_VERSION 2 // Max. comms packet version supported by this open_mower LL FW #define LL_HIGH_LEVEL_CONFIG_BIT_DFPIS5V 1 << 0 // Enable full sound via mower_config env var "OM_DFP_IS_5V" #define LL_HIGH_LEVEL_CONFIG_BIT_EMERGENCY_INVERSE 1 << 1 // Sample, for possible future usage, i.e. for SA-Type emergency typedef char iso639_1[2]; // Two char ISO 639-1 language code +// FIXME: Better name than HallMode? +enum class HallMode { + off = 0, + lift, + tilt, + stop, + pause +}; + +// Bi-directional LL/HL config packet #pragma pack(push, 1) struct ll_high_level_config { uint8_t type; @@ -154,4 +165,20 @@ struct ll_high_level_config { } __attribute__((packed)); #pragma pack(pop) +// Uni-directional HL->LL config packet extension v2, active since ll_high_level_config.comms_version >= 2 +// (this might change to an Bi-directional packet if HL needs feedback for one of these fields) +#pragma pack(push, 1) +struct ll_high_level_config_ext_v2 { + float v_charge_max; // Max. charging voltage before charging get switched off + float i_charge_max; // Max. charging current before charging get switched off + float v_battery_max; // Max. battery voltage before charging get switched off + uint32_t halls_config; // HallMode per [0:2] OM-Hall-1 ... [9:11] OM-Hall-4, [12:14] Stock-CoverUI-1 ... [27:29] Stock-CoverUI-6 (0xFFFFFF do not change) + uint16_t halls_inverted; // 0 = Active high, 1 = Active low (inverted). [0] OM-Hall-1 ... [9] Stock-CoverUI-6. ATTENTION: Opposite than current logic (0xFFFF do not change) + uint16_t lift_period; // Period (ms) for both wheels to be lifted in order to count as emergency (0 disable, 0xFFFF do not change). This is to filter uneven ground + uint16_t tilt_period; // Period (ms) for a single wheel to be lifted in order to count as emergency (0 disable, 0xFFFF do not change). This is to filter uneven ground + uint32_t spare1; // Spare for future use + uint16_t crc; +} __attribute__((packed)); +#pragma pack(pop) + #endif diff --git a/Firmware/LowLevel/src/main.cpp b/Firmware/LowLevel/src/main.cpp index af31c60a..49a5b0b2 100644 --- a/Firmware/LowLevel/src/main.cpp +++ b/Firmware/LowLevel/src/main.cpp @@ -22,6 +22,7 @@ #include "pins.h" #include "ui_board.h" #include "imu.h" +#include "nv_config.h" #ifdef ENABLE_SOUND_MODULE #include @@ -62,6 +63,11 @@ SerialPIO uiSerial(PIN_UI_TX, PIN_UI_RX, 250); #define R_SHUNT 0.003f #define CURRENT_SENSE_GAIN 100.0f +#define V_CHARGE_MAX 30.0f // Default YF-C500 max. charge voltage +#define I_CHARGE_MAX 1.5f // Default YF-C500 max. charge current +#define V_CHARGE_ABS_MAX 40.0f // Absolute max. limited by D2/D3 Schottky +#define I_CHARGE_ABS_MAX 5.0f // Absolute max. limited by D2/D3 Schottky + #define BATT_ABS_MAX 28.7f #define BATT_ABS_Min 21.7f @@ -123,6 +129,18 @@ uint16_t ui_version = 0; // Last received UI firmware version uint8_t ui_topic_bitmask = Topic_set_leds; // UI subscription, default to Set_LEDs uint16_t ui_interval = 1000; // UI send msg (LED/State) interval (ms) +// Some default thresholds (might be overwritten by HL config packet) +struct ll_high_level_config_ext_v2 config_v2 = { + .v_charge_max = V_CHARGE_MAX, // Max. charging voltage before charging get switched off + .i_charge_max = I_CHARGE_MAX, // Max. charging current before charging get switched off + .v_battery_max = 29.0f, // Max. battery voltage before charging get switched off + .halls_config = 0, // TODO: Add OM-YF-C500 defaults + .halls_inverted = 0, // TODO: Add OM-YF-C500 defaults + .lift_period = LIFT_EMERGENCY_MILLIS, + .tilt_period = TILT_EMERGENCY_MILLIS}; + +nv_config::Config *nv_cfg; // Non-volatile configuration + // Some vars related to PACKET_ID_LL_HIGH_LEVEL_CONFIG_* uint8_t comms_version = 0; // comms packet version (>0 if implemented) uint8_t config_bitmask = 0; // See LL_HIGH_LEVEL_CONFIG_BIT_* @@ -590,17 +608,40 @@ void onPacketReceived(const uint8_t *buffer, size_t size) { } else if (buffer[0] == PACKET_ID_LL_HIGH_LEVEL_STATE && size == sizeof(struct ll_high_level_state)) { // copy the state last_high_level_state = *((struct ll_high_level_state *) buffer); - } - else if ((buffer[0] == PACKET_ID_LL_HIGH_LEVEL_CONFIG_REQ || buffer[0] == PACKET_ID_LL_HIGH_LEVEL_CONFIG_RSP) && size == sizeof(struct ll_high_level_config)) - { + } else if ((buffer[0] == PACKET_ID_LL_HIGH_LEVEL_CONFIG_REQ || buffer[0] == PACKET_ID_LL_HIGH_LEVEL_CONFIG_RSP) && + (size == sizeof(struct ll_high_level_config) || size == sizeof(struct ll_high_level_config) + sizeof(struct ll_high_level_config_ext_v2))) { // Read and handle received config struct ll_high_level_config *pkt = (struct ll_high_level_config *)buffer; - if (pkt->comms_version <= LL_HIGH_LEVEL_CONFIG_MAX_COMMS_VERSION) - comms_version = pkt->comms_version; - else - comms_version = LL_HIGH_LEVEL_CONFIG_MAX_COMMS_VERSION; - config_bitmask = pkt->config_bitmask; // Take over as sent. HL is leading (for now) - // FIXME: Assign volume & language if not already stored in flash-config + // Lower comms_version is leading + pkt->comms_version <= LL_HIGH_LEVEL_CONFIG_MAX_COMMS_VERSION ? comms_version = pkt->comms_version : comms_version = LL_HIGH_LEVEL_CONFIG_MAX_COMMS_VERSION; + config_bitmask = pkt->config_bitmask; // Take over as sent. HL is leading (for now) + + // PR-80: Assign volume & language if not already stored in flash-config + + // Handle possible ll_high_level_config_ext_v2 extension + if (comms_version >= 2) { + // Read and handle extension v2 + struct ll_high_level_config_ext_v2 *pkt = (struct ll_high_level_config_ext_v2 *)buffer + sizeof(struct ll_high_level_config); + + // Fix exceed of absolute max. values + pkt->v_charge_max = min(pkt->v_charge_max, V_CHARGE_ABS_MAX); + pkt->i_charge_max = min(pkt->i_charge_max, I_CHARGE_ABS_MAX); + + // Copy extension packet to config_v2 + config_v2 = *((struct ll_high_level_config_ext_v2 *)buffer + sizeof(struct ll_high_level_config)); + + // TODO: Parse hall config fields and build a compact iterable vector/array/... of active hall inputs or do it directly in updateEmergency() + + // TODO: Decide which fields should get stored in nv_config (flash) so that it's directly avail after power-up (without the need of ros_running) + // My current thoughts are: + // v_charge_max for those who need a much lower or higher charging voltage, so that battery doesn't get empty or overload if ROS is offline for a longer period (or silently crashed) + // i_charge is similar. If one has a higher current DCDC and dock his empty mower, it should charge, even if ROS is down + // v_battery_max for sure (overcharge protection) + // + // but NOT: + // halls_config/inverted? Think we should always start with default OM halls config but if comms_version >= 2, wait till v2 packet extension got received. + // tilt/lift periods + } if (buffer[0] == PACKET_ID_LL_HIGH_LEVEL_CONFIG_REQ) sendConfigMessage(PACKET_ID_LL_HIGH_LEVEL_CONFIG_RSP); @@ -609,7 +650,7 @@ void onPacketReceived(const uint8_t *buffer, size_t size) { // returns true, if it's a good idea to charge the battery (current, voltages, ...) bool checkShouldCharge() { - return status_message.v_charge < 30.0 && status_message.charging_current < 1.5 && status_message.v_battery < 29.0; + return status_message.v_charge < config_v2.v_charge_max && status_message.charging_current < config_v2.i_charge_max && status_message.v_battery < config_v2.v_battery_max; } void updateChargingEnabled() { From e19c9527f2817eaaf27c27aa6a659c957b60950f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?J=C3=B6rg=20Ebeling?= Date: Mon, 7 Oct 2024 23:51:37 +0200 Subject: [PATCH 02/32] Add missing files --- Firmware/LowLevel/include/debug.h | 47 ++++++++ Firmware/LowLevel/src/main.cpp | 1 + Firmware/LowLevel/src/nv_config.cpp | 181 ++++++++++++++++++++++++++++ 3 files changed, 229 insertions(+) create mode 100644 Firmware/LowLevel/include/debug.h create mode 100644 Firmware/LowLevel/src/nv_config.cpp diff --git a/Firmware/LowLevel/include/debug.h b/Firmware/LowLevel/include/debug.h new file mode 100644 index 00000000..731f9641 --- /dev/null +++ b/Firmware/LowLevel/include/debug.h @@ -0,0 +1,47 @@ +// Created by Apehaenger on 02/02/23. +// +// This work is licensed under a Creative Commons Attribution-NonCommercial-ShareAlike 4.0 International License. +// +// Feel free to use the design in your private/educational projects, but don't try to sell the design or products based on it without getting my consent first. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +// SOFTWARE. +// +// +#ifndef _DEBUG_H_ +#define _DEBUG_H_ + +// Define to stream debugging messages via USB +//#define USB_DEBUG +#define DEBUG_PREFIX "" // You may define a debug prefix string + +#ifdef USB_DEBUG +#define DEBUG_SERIAL Serial +// #define DfMiniMp3Debug DEBUG_SERIAL // Also output DFPlayer IN/OUT cmd data + +// Some bloody simple debug macros which superfluous '#ifdef USB_DEBUG' ... +#define DEBUG_BEGIN(b) \ + DEBUG_SERIAL.begin(b); \ + while (!DEBUG_SERIAL) \ + ; +#define DEBUG_PRINTF(fmt, ...) \ + do \ + { \ + DEBUG_SERIAL.printf(DEBUG_PREFIX fmt, ##__VA_ARGS__); \ + } while (0) +#else +#define DEBUG_BEGIN(b) +#define DEBUG_PRINTF(fmt, ...) +#endif + +#define PRINTF_BINARY_PATTERN_INT8 "%c%c%c%c%c%c%c%c" +#define PRINTF_BYTE_TO_BINARY_INT8(i) \ + (((i)&0x80ll) ? '1' : '0'), (((i)&0x40ll) ? '1' : '0'), (((i)&0x20ll) ? '1' : '0'), (((i)&0x10ll) ? '1' : '0'), \ + (((i)&0x08ll) ? '1' : '0'), (((i)&0x04ll) ? '1' : '0'), (((i)&0x02ll) ? '1' : '0'), (((i)&0x01ll) ? '1' : '0') + +#endif // _DEBUG_H_ diff --git a/Firmware/LowLevel/src/main.cpp b/Firmware/LowLevel/src/main.cpp index 49a5b0b2..54d1b041 100644 --- a/Firmware/LowLevel/src/main.cpp +++ b/Firmware/LowLevel/src/main.cpp @@ -22,6 +22,7 @@ #include "pins.h" #include "ui_board.h" #include "imu.h" +#include "debug.h" #include "nv_config.h" #ifdef ENABLE_SOUND_MODULE diff --git a/Firmware/LowLevel/src/nv_config.cpp b/Firmware/LowLevel/src/nv_config.cpp new file mode 100644 index 00000000..054e9381 --- /dev/null +++ b/Firmware/LowLevel/src/nv_config.cpp @@ -0,0 +1,181 @@ +/* + * Copyright 2024 Jörg Ebeling (Apehaenger) + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in all + * copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE.* Testing/examples for reading/writing flash on the RP2040. + * + * Heavily inspired, copied from, as well as must-read: + * https://github.com/MakerMatrix/RP2040_flash_programming + */ +#include "nv_config.h" + +#include + +#include + +#include "debug.h" + +extern "C" { +#include +#include +}; + +#define FLASH_TARGET_OFFSET (PICO_FLASH_SIZE_BYTES - FLASH_SECTOR_SIZE) // Target offset to the last sector of flash +#define NV_MIN_RECORD_SIZE (sizeof(Record) - sizeof(Config)) // Minimum Record size (Record size without Config member) +#define NV_PAGES_IN_SECTOR (FLASH_SECTOR_SIZE / FLASH_PAGE_SIZE) // How much pages fit into one sector +#define NV_RECORD_CRC_DATALEN (sizeof(Record) - sizeof(Config) - sizeof(cur_record.crc)) + +#ifdef DEBUG_PREFIX +#undef DEBUG_PREFIX +#define DEBUG_PREFIX "[NVC] " +#endif + +namespace nv_config { +static_assert(sizeof(Record) <= FLASH_PAGE_SIZE, "Record struct size larger than page size"); + +int first_empty_page = -1; // First empty page in sector +int last_used_page = -1; // Last used page with non-empty data +int last_record_pos = -1; // Last record position within page (page_buf) + +uint8_t page_buf[FLASH_PAGE_SIZE]; // Page buffer required for subsequential flash_range_program() of the same page +Record cur_record; // Current (last or (if there hasn't been a Record flashed before) default) Record +uint16_t config_crc; // CRC of current Record->config used for config change detection + +FastCRC16 CRC16; + +unsigned long next_save_millis = millis() + NV_CONFIG_MAX_SAVE_INTERVAL; + +Config *get() { + DEBUG_PRINTF("FLASH_PAGE_SIZE: %d, FLASH_SECTOR_SIZE: %d, FLASH_BLOCK_SIZE: %d, PICO_FLASH_SIZE_BYTES: %d, XIP_BASE: 0x%x, FLASH_TARGET_OFFSET: %d\n", + FLASH_PAGE_SIZE, FLASH_SECTOR_SIZE, FLASH_BLOCK_SIZE, PICO_FLASH_SIZE_BYTES, XIP_BASE, FLASH_TARGET_OFFSET); + DEBUG_PRINTF("NV_PAGES_IN_SECTOR: %d, sizeof(Record): %d, sizeof(Config): %d, possible num of records within one page: %d\n", + NV_PAGES_IN_SECTOR, sizeof(Record), sizeof(Config), FLASH_PAGE_SIZE / sizeof(Record)); + + // Read flash until first empty page found + int addr; + unsigned int page; + int32_t *p; + for (page = 0; page < FLASH_SECTOR_SIZE / FLASH_PAGE_SIZE; page++) { + p = (int32_t *)(XIP_BASE + FLASH_TARGET_OFFSET + (page * FLASH_PAGE_SIZE)); + + // 0xFFFFFFFF cast as an int is -1 so this is how we detect an empty page + DEBUG_PRINTF("Page %d (0x%x): record_id = %ld (0x%lx)\n", page, int(p), *p, *p); + if (*p == -1 && first_empty_page < 0) { + first_empty_page = page; + break; + } + last_used_page = page; + } + DEBUG_PRINTF("last_used_page %d, first_empty_page %d\n", last_used_page, first_empty_page); + + // Find last written Record + if (last_used_page >= 0) { + // RLoop over last_used_page to find latest record via it's record.id + DEBUG_PRINTF("Last possible record (unaligned) = FLASH_PAGE_SIZE %d - NV_MIN_RECORD_SIZE %d = %u\n", FLASH_PAGE_SIZE, NV_MIN_RECORD_SIZE, FLASH_PAGE_SIZE - NV_MIN_RECORD_SIZE); + int addr = XIP_BASE + FLASH_TARGET_OFFSET + (last_used_page * FLASH_PAGE_SIZE); + // Calc last possible record offset without config, for the case that Record.config get changed, and pointer-align to "next multiple of" + int last_possible_record_offset = (FLASH_PAGE_SIZE - NV_MIN_RECORD_SIZE) - ((FLASH_PAGE_SIZE - NV_MIN_RECORD_SIZE) % NV_RECORD_ALIGNMENT) + NV_RECORD_ALIGNMENT; + DEBUG_PRINTF("last_possible_record_offset (aligned) 0x%x for Record.id alignment of %d\n", last_possible_record_offset, NV_RECORD_ALIGNMENT); + // Record test_record; + for (size_t i = last_possible_record_offset; i >= 0; i = i - NV_RECORD_ALIGNMENT) { + uint32_t *p = (uint32_t *)(addr + i); + if (*p != NV_RECORD_ID) + continue; + + // Validate if the found NV_RECORD_ID is a valid Record.id + DEBUG_PRINTF("Page %d, offset 0x%x (at %p): Record.id prospect = 0x%lx\n", last_used_page, i, p, *p); + Record test_record; + memcpy(&test_record, (uint8_t *)p, sizeof(Record)); + DEBUG_PRINTF("Test- Record: num_sector_erase: %ld, num_page_write: %ld, crc: 0x%lx\n", test_record.num_sector_erase, test_record.num_page_write, test_record.crc); + uint16_t test_crc = CRC16.ccitt((uint8_t *)&test_record, NV_RECORD_CRC_DATALEN); + DEBUG_PRINTF("Test- Record CRC 0x%x of datalen %d\n", test_crc, NV_RECORD_CRC_DATALEN); + if (test_crc != test_record.crc) + continue; + + DEBUG_PRINTF("Test- Record is valid. Buffer the full flash page\n"); + memcpy(&page_buf, (uint8_t *)addr, FLASH_PAGE_SIZE); + memcpy(&cur_record, &test_record, sizeof(Record)); + last_record_pos = i; + break; + } + } + DEBUG_PRINTF("Last (or default) config's volume: %d\n", cur_record.config.volume); + + // CRC for simple checking if config has changed + config_crc = CRC16.ccitt((uint8_t *)&cur_record.config, sizeof(Config)); + DEBUG_PRINTF("cur_record.config CRC: 0x%x\n", config_crc); + + return &cur_record.config; +} + +void delayedSaveChanges() { + // Wear level protection + if (millis() < next_save_millis) + return; + next_save_millis = millis() + NV_CONFIG_MAX_SAVE_INTERVAL; + + // Check CRC if config changed + uint16_t check_crc = CRC16.ccitt((uint8_t *)&cur_record.config, sizeof(Config)); + DEBUG_PRINTF("Actual- vs. stored- config CRC: 0x%x ?= 0x%x\n", check_crc, config_crc); + if (check_crc == config_crc) + return; // Record.config doesn't changed + + // Prepare record position within page buffer + if (last_record_pos == -1) + last_record_pos = 0; + else { + last_record_pos += sizeof(Record); + last_record_pos = last_record_pos - (last_record_pos % NV_RECORD_ALIGNMENT) + NV_RECORD_ALIGNMENT; // Adjust to "next multiple of" NV_RECORD_ALIGNMENT + } + if ((last_record_pos + sizeof(Record)) > FLASH_PAGE_SIZE) { + // Will not fit into the current page anymore + last_used_page++; + last_record_pos = 0; + first_empty_page++; + std::fill_n(page_buf, FLASH_PAGE_SIZE, 0xff); // Mark page buffer as (flash) erased + } + + // If no empty page got found during get(), or last page got eaten, let's erase our flash sector + if (first_empty_page < 0 || last_used_page >= NV_PAGES_IN_SECTOR) { + DEBUG_PRINTF("Full sector, erase...\n"); + uint32_t ints = save_and_disable_interrupts(); + flash_range_erase(FLASH_TARGET_OFFSET, FLASH_SECTOR_SIZE); + restore_interrupts(ints); + // Reset positioning vars + last_used_page = 0; + first_empty_page = 0; + cur_record.num_sector_erase++; + std::fill_n(page_buf, FLASH_PAGE_SIZE, 0xff); // Mark page buffer as (flash) erased + } + + // Prepare record + cur_record.num_page_write++; + cur_record.crc = CRC16.ccitt((uint8_t *)&cur_record, NV_RECORD_CRC_DATALEN); + DEBUG_PRINTF("Record CRC 0x%x of datalen %d\n", cur_record.crc, NV_RECORD_CRC_DATALEN); + + // memcopy cur_record to page buffer + memcpy(&page_buf[last_record_pos], &cur_record, sizeof(Record)); + + // Write page to flash + DEBUG_PRINTF("Write to page %d, with new record pos %d: volume %d...\n", last_used_page, last_record_pos, cur_record.config.volume); + uint32_t ints = save_and_disable_interrupts(); + flash_range_program(FLASH_TARGET_OFFSET + (last_used_page * FLASH_PAGE_SIZE), (uint8_t *)page_buf, sizeof(page_buf)); + restore_interrupts(ints); + config_crc = check_crc; // Update last saved config CRC +} +} // namespace nv_config \ No newline at end of file From f3936e6e35659c8bfd5a81fe86cfa8f6b1b19b17 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?J=C3=B6rg=20Ebeling?= Date: Wed, 9 Oct 2024 22:04:01 +0200 Subject: [PATCH 03/32] Abort one large config struct consideration --- Firmware/LowLevel/include/config.h | 13 ++++++ Firmware/LowLevel/src/datatypes.h | 63 ++++++++++++++++-------------- Firmware/LowLevel/src/main.cpp | 55 +++++++++++++++----------- 3 files changed, 80 insertions(+), 51 deletions(-) create mode 100644 Firmware/LowLevel/include/config.h diff --git a/Firmware/LowLevel/include/config.h b/Firmware/LowLevel/include/config.h new file mode 100644 index 00000000..fca0cf56 --- /dev/null +++ b/Firmware/LowLevel/include/config.h @@ -0,0 +1,13 @@ +#ifndef _CONFIG_H +#define _CONFIG_H + +#define TILT_EMERGENCY_MILLIS 2500 // Time for a single wheel to be lifted in order to count as emergency (0 disable). This is to filter uneven ground. +#define LIFT_EMERGENCY_MILLIS 100 // Time for both wheels to be lifted in order to count as emergency (0 disable). This is to filter uneven ground. + +#define V_CHARGE_MAX 30.0f // Default YF-C500 max. charge voltage +#define I_CHARGE_MAX 1.5f // Default YF-C500 max. charge current + +#define V_CHARGE_ABS_MAX 40.0f // Absolute max. limited by D2/D3 Schottky +#define I_CHARGE_ABS_MAX 5.0f // Absolute max. limited by D2/D3 Schottky + +#endif // _CONFIG_H \ No newline at end of file diff --git a/Firmware/LowLevel/src/datatypes.h b/Firmware/LowLevel/src/datatypes.h index cbc1a39b..dff7706c 100644 --- a/Firmware/LowLevel/src/datatypes.h +++ b/Firmware/LowLevel/src/datatypes.h @@ -19,6 +19,7 @@ #define _DATATYPES_H #include +#include "config.h" #define PACKET_ID_LL_STATUS 1 #define PACKET_ID_LL_IMU 2 @@ -136,48 +137,52 @@ struct ll_ui_event { } __attribute__((packed)); #pragma pack(pop) -#define LL_HIGH_LEVEL_CONFIG_MAX_COMMS_VERSION 2 // Max. comms packet version supported by this open_mower LL FW #define LL_HIGH_LEVEL_CONFIG_BIT_DFPIS5V 1 << 0 // Enable full sound via mower_config env var "OM_DFP_IS_5V" -#define LL_HIGH_LEVEL_CONFIG_BIT_EMERGENCY_INVERSE 1 << 1 // Sample, for possible future usage, i.e. for SA-Type emergency +#define LL_HIGH_LEVEL_CONFIG_BIT_BACKGROUND_SOUNDS 1 << 1 // Enable background sounds typedef char iso639_1[2]; // Two char ISO 639-1 language code -// FIXME: Better name than HallMode? -enum class HallMode { +enum class HallMode : unsigned int { off = 0, - lift, - tilt, + emergency, // lift & tilt stop, pause }; -// Bi-directional LL/HL config packet +// FIXME: Decide later which is more comfortable activeLow = 0 | 1 +enum class HallLevel : unsigned int { + activeLow = 0, // If Hall-Sensor (or button) is active/triggered we've this level on our GPIO + activeHigh +}; + +struct HallConfig { + HallMode mode : 4 {0}; + HallLevel level : 1 {0}; +}; + +#define MAX_HALL_INPUTS 14 // How much Hall-inputs we support. 4 * OM + 6 * Stock-CoverUI + 4 spare + +// LL/HL config packet, bi-directional, flexible-length, with defaults for YF-C500 #pragma pack(push, 1) struct ll_high_level_config { uint8_t type; - uint8_t comms_version = LL_HIGH_LEVEL_CONFIG_MAX_COMMS_VERSION; // Increasing comms packet-version number for packet compatibility (n > 0) - uint8_t config_bitmask = 0; // See LL_HIGH_LEVEL_CONFIG_BIT_* - int8_t volume; // Volume (0-100%) feedback (if directly changed via CoverUI) - iso639_1 language; // ISO 639-1 (2-char) language code (en, de, ...) - uint16_t spare1 = 0; // Spare for future use - uint16_t spare2 = 0; // Spare for future use - uint16_t crc; -} __attribute__((packed)); -#pragma pack(pop) - -// Uni-directional HL->LL config packet extension v2, active since ll_high_level_config.comms_version >= 2 -// (this might change to an Bi-directional packet if HL needs feedback for one of these fields) -#pragma pack(push, 1) -struct ll_high_level_config_ext_v2 { - float v_charge_max; // Max. charging voltage before charging get switched off - float i_charge_max; // Max. charging current before charging get switched off - float v_battery_max; // Max. battery voltage before charging get switched off - uint32_t halls_config; // HallMode per [0:2] OM-Hall-1 ... [9:11] OM-Hall-4, [12:14] Stock-CoverUI-1 ... [27:29] Stock-CoverUI-6 (0xFFFFFF do not change) - uint16_t halls_inverted; // 0 = Active high, 1 = Active low (inverted). [0] OM-Hall-1 ... [9] Stock-CoverUI-6. ATTENTION: Opposite than current logic (0xFFFF do not change) - uint16_t lift_period; // Period (ms) for both wheels to be lifted in order to count as emergency (0 disable, 0xFFFF do not change). This is to filter uneven ground - uint16_t tilt_period; // Period (ms) for a single wheel to be lifted in order to count as emergency (0 disable, 0xFFFF do not change). This is to filter uneven ground - uint32_t spare1; // Spare for future use uint16_t crc; + uint8_t config_bitmask = 0; // See LL_HIGH_LEVEL_CONFIG_BIT_* + int8_t volume = 80; // Volume (0-100%) feedback (if directly changed via CoverUI) + iso639_1 language = {'e', 'n'}; // ISO 639-1 (2-char) language code (en, de, ...) + float v_charge_max = V_CHARGE_MAX; // Max. charging voltage before charging get switched off + float i_charge_max = I_CHARGE_MAX; // Max. charging current before charging get switched off + float v_battery_max = 29.0f; // Max. battery voltage before charging get switched off + uint16_t lift_period = LIFT_EMERGENCY_MILLIS; // Period (ms) for both wheels to be lifted in order to count as emergency (0 disable, 0xFFFF do not change). This is to filter uneven ground + uint16_t tilt_period = TILT_EMERGENCY_MILLIS; // Period (ms) for a single wheel to be lifted in order to count as emergency (0 disable, 0xFFFF do not change). This is to filter uneven ground + HallConfig hall_configs[MAX_HALL_INPUTS] = { + {HallMode::emergency, HallLevel::activeLow}, // [0] OM Hall-1 input + {HallMode::emergency, HallLevel::activeLow}, // [1] OM Hall-2 input + {HallMode::stop, HallLevel::activeLow}, // [2] OM Hall-3 input + {HallMode::stop, HallLevel::activeLow}, // [3] OM Hall-4 input + // [4] Stock-CoverUI-1 ... [9] Stock-CoverUI-6 defaults to off + }; + // INFO: Before adding a new member: Do we need to add some hall_config spares? } __attribute__((packed)); #pragma pack(pop) diff --git a/Firmware/LowLevel/src/main.cpp b/Firmware/LowLevel/src/main.cpp index 54d1b041..5e314cbf 100644 --- a/Firmware/LowLevel/src/main.cpp +++ b/Firmware/LowLevel/src/main.cpp @@ -19,6 +19,7 @@ #include #include #include "datatypes.h" +#include "config.h" #include "pins.h" #include "ui_board.h" #include "imu.h" @@ -34,8 +35,6 @@ #define UI_GET_VERSION_CYCLETIME 5000 // cycletime for UI Get_Version request (UI available check) #define UI_GET_VERSION_TIMEOUT 100 // timeout for UI Get_Version response (UI available check) -#define TILT_EMERGENCY_MILLIS 2500 // Time for a single wheel to be lifted in order to count as emergency (0 disable). This is to filter uneven ground. -#define LIFT_EMERGENCY_MILLIS 100 // Time for both wheels to be lifted in order to count as emergency (0 disable). This is to filter uneven ground. #define BUTTON_EMERGENCY_MILLIS 20 // Time for button emergency to activate. This is to debounce the button. // Define to stream debugging messages via USB @@ -64,11 +63,6 @@ SerialPIO uiSerial(PIN_UI_TX, PIN_UI_RX, 250); #define R_SHUNT 0.003f #define CURRENT_SENSE_GAIN 100.0f -#define V_CHARGE_MAX 30.0f // Default YF-C500 max. charge voltage -#define I_CHARGE_MAX 1.5f // Default YF-C500 max. charge current -#define V_CHARGE_ABS_MAX 40.0f // Absolute max. limited by D2/D3 Schottky -#define I_CHARGE_ABS_MAX 5.0f // Absolute max. limited by D2/D3 Schottky - #define BATT_ABS_MAX 28.7f #define BATT_ABS_Min 21.7f @@ -130,17 +124,8 @@ uint16_t ui_version = 0; // Last received UI firmware version uint8_t ui_topic_bitmask = Topic_set_leds; // UI subscription, default to Set_LEDs uint16_t ui_interval = 1000; // UI send msg (LED/State) interval (ms) -// Some default thresholds (might be overwritten by HL config packet) -struct ll_high_level_config_ext_v2 config_v2 = { - .v_charge_max = V_CHARGE_MAX, // Max. charging voltage before charging get switched off - .i_charge_max = I_CHARGE_MAX, // Max. charging current before charging get switched off - .v_battery_max = 29.0f, // Max. battery voltage before charging get switched off - .halls_config = 0, // TODO: Add OM-YF-C500 defaults - .halls_inverted = 0, // TODO: Add OM-YF-C500 defaults - .lift_period = LIFT_EMERGENCY_MILLIS, - .tilt_period = TILT_EMERGENCY_MILLIS}; - -nv_config::Config *nv_cfg; // Non-volatile configuration +struct ll_high_level_config llhl_config; // LL/HL configuration (get initialized with YF-C500 defaults) +nv_config::Config *nv_cfg; // Non-volatile configuration // Some vars related to PACKET_ID_LL_HIGH_LEVEL_CONFIG_* uint8_t comms_version = 0; // comms packet version (>0 if implemented) @@ -581,11 +566,37 @@ void onPacketReceived(const uint8_t *buffer, size_t size) { return; // check the CRC - uint16_t crc = CRC16.ccitt(buffer, size - 2); + uint16_t crc; + + // @ClemensElflein: Here is why I decided against having CRC at first packet member: + // We need to select between the two CRC positions. But if CRC would be on first place, type would go somewhere behind it. + // But then type for this packet would be on a position where the other packets place their data(or CRC). This would + // quickly result in wrong packet-type identifications. + // Could also be solved, but would complicate code and double CRC calculations for the packets which got identified wrong. + // The alternative I do see could be a cascaded CRC calculation: + // Nearly 99.99% of all packets have their packet at the end, so we always could try that first, but when it fails, + // we could fall back and try with CRC on first position to see if it's this one-time packet. + // But I would prefer this more strict and defined way. + + // We have two CRC position variants + if (buffer[0] == PACKET_ID_LL_HIGH_LEVEL_CONFIG_REQ || buffer[0] == PACKET_ID_LL_HIGH_LEVEL_CONFIG_RSP) { + // Flexible length packet, where the CRC follows the type and type is NOT part of the CRC. + + // Comment: This is just as safe as including the type into the CRC because: If type would be accidentally wrong, + // then it also wouldn't validate in the "else" CRC calculation where type is included + crc = CRC16.ccitt(buffer + 3, size - 3); + + if (buffer[1] != ((crc >> 8) & 0xFF) || + buffer[2] != (crc & 0xFF)) + return; + } else { + // Normal, fixed length packet, where the CRC is the last member + crc = CRC16.ccitt(buffer, size - 2); - if (buffer[size - 1] != ((crc >> 8) & 0xFF) || - buffer[size - 2] != (crc & 0xFF)) - return; + if (buffer[size - 1] != ((crc >> 8) & 0xFF) || + buffer[size - 2] != (crc & 0xFF)) + return; + } if (buffer[0] == PACKET_ID_LL_HEARTBEAT && size == sizeof(struct ll_heartbeat)) { From d90b6ca77aeed45d12de60171b5093a6c07bb183 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?J=C3=B6rg=20Ebeling?= Date: Thu, 10 Oct 2024 23:31:27 +0200 Subject: [PATCH 04/32] Finish flexible length config packet --- Firmware/LowLevel/src/datatypes.h | 25 ++++--- Firmware/LowLevel/src/main.cpp | 107 +++++++++--------------------- 2 files changed, 47 insertions(+), 85 deletions(-) diff --git a/Firmware/LowLevel/src/datatypes.h b/Firmware/LowLevel/src/datatypes.h index dff7706c..e58ec351 100644 --- a/Firmware/LowLevel/src/datatypes.h +++ b/Firmware/LowLevel/src/datatypes.h @@ -142,31 +142,34 @@ struct ll_ui_event { typedef char iso639_1[2]; // Two char ISO 639-1 language code -enum class HallMode : unsigned int { +enum class HallMode : uint8_t { off = 0, emergency, // lift & tilt stop, pause }; -// FIXME: Decide later which is more comfortable activeLow = 0 | 1 -enum class HallLevel : unsigned int { +// FIXME: Decide later which is more comfortable, activeLow = 0 | 1 +enum class HallLevel : uint8_t { activeLow = 0, // If Hall-Sensor (or button) is active/triggered we've this level on our GPIO activeHigh }; +#pragma pack(push, 1) struct HallConfig { - HallMode mode : 4 {0}; - HallLevel level : 1 {0}; -}; + HallMode mode : 4; + HallLevel level : 1; +} __attribute__((packed)); +#pragma pack(pop) -#define MAX_HALL_INPUTS 14 // How much Hall-inputs we support. 4 * OM + 6 * Stock-CoverUI + 4 spare +#define MAX_HALL_INPUTS 10 // How much Hall-inputs we support. 4 * OM + 6 * Stock-CoverUI + 0 spare (because not yet required to make it fixed) -// LL/HL config packet, bi-directional, flexible-length, with defaults for YF-C500 +// LL/HL config packet, encapsulated in wire_msg for transfer, bi-directional, flexible-length, with defaults for YF-C500. #pragma pack(push, 1) struct ll_high_level_config { - uint8_t type; - uint16_t crc; + // ATTENTION: This is a flexible length struct. It is allowed to grow independently to HL without loosing compatibility, + // but never change or restructure already published member, except you really know their consequences. + uint8_t comms_version = 1; // Transitional comms_version, can safely renamed as spare for other use in, let's say 2025 ;-) uint8_t config_bitmask = 0; // See LL_HIGH_LEVEL_CONFIG_BIT_* int8_t volume = 80; // Volume (0-100%) feedback (if directly changed via CoverUI) iso639_1 language = {'e', 'n'}; // ISO 639-1 (2-char) language code (en, de, ...) @@ -182,7 +185,7 @@ struct ll_high_level_config { {HallMode::stop, HallLevel::activeLow}, // [3] OM Hall-4 input // [4] Stock-CoverUI-1 ... [9] Stock-CoverUI-6 defaults to off }; - // INFO: Before adding a new member: Do we need to add some hall_config spares? + // INFO: Before adding a new member here: Decide if and how much hall_configs spares do we like to have } __attribute__((packed)); #pragma pack(pop) diff --git a/Firmware/LowLevel/src/main.cpp b/Firmware/LowLevel/src/main.cpp index 5e314cbf..17ea9a9a 100644 --- a/Firmware/LowLevel/src/main.cpp +++ b/Firmware/LowLevel/src/main.cpp @@ -124,13 +124,9 @@ uint16_t ui_version = 0; // Last received UI firmware version uint8_t ui_topic_bitmask = Topic_set_leds; // UI subscription, default to Set_LEDs uint16_t ui_interval = 1000; // UI send msg (LED/State) interval (ms) -struct ll_high_level_config llhl_config; // LL/HL configuration (get initialized with YF-C500 defaults) +struct ll_high_level_config llhl_config; // LL/HL configuration (is initialized with YF-C500 defaults) nv_config::Config *nv_cfg; // Non-volatile configuration -// Some vars related to PACKET_ID_LL_HIGH_LEVEL_CONFIG_* -uint8_t comms_version = 0; // comms packet version (>0 if implemented) -uint8_t config_bitmask = 0; // See LL_HIGH_LEVEL_CONFIG_BIT_* - void sendMessage(void *message, size_t size); void sendUIMessage(void *message, size_t size); void onPacketReceived(const uint8_t *buffer, size_t size); @@ -552,12 +548,14 @@ void onUIPacketReceived(const uint8_t *buffer, size_t size) { } void sendConfigMessage(uint8_t pkt_type) { - struct ll_high_level_config ll_config; - ll_config.type = pkt_type; - ll_config.config_bitmask = config_bitmask; - ll_config.volume = 80; // FIXME: Adapt once nv_config or improve-sound got merged - strncpy(ll_config.language, "en", 2); // FIXME: Adapt once nv_config or improve-sound got merged - sendMessage(&ll_config, sizeof(struct ll_high_level_config)); + size_t msg_size = sizeof(struct ll_high_level_config) + 3; // + 1 type + 2 crc + uint8_t *msg = (uint8_t *)malloc(msg_size); + if (msg == NULL) + return; // malloc() failed + *msg = pkt_type; + memcpy(msg + 1, &llhl_config, sizeof(struct ll_high_level_config)); // Copy our live config into the message, behind type + sendMessage(msg, msg_size); + free(msg); } void onPacketReceived(const uint8_t *buffer, size_t size) { @@ -566,37 +564,11 @@ void onPacketReceived(const uint8_t *buffer, size_t size) { return; // check the CRC - uint16_t crc; - - // @ClemensElflein: Here is why I decided against having CRC at first packet member: - // We need to select between the two CRC positions. But if CRC would be on first place, type would go somewhere behind it. - // But then type for this packet would be on a position where the other packets place their data(or CRC). This would - // quickly result in wrong packet-type identifications. - // Could also be solved, but would complicate code and double CRC calculations for the packets which got identified wrong. - // The alternative I do see could be a cascaded CRC calculation: - // Nearly 99.99% of all packets have their packet at the end, so we always could try that first, but when it fails, - // we could fall back and try with CRC on first position to see if it's this one-time packet. - // But I would prefer this more strict and defined way. - - // We have two CRC position variants - if (buffer[0] == PACKET_ID_LL_HIGH_LEVEL_CONFIG_REQ || buffer[0] == PACKET_ID_LL_HIGH_LEVEL_CONFIG_RSP) { - // Flexible length packet, where the CRC follows the type and type is NOT part of the CRC. - - // Comment: This is just as safe as including the type into the CRC because: If type would be accidentally wrong, - // then it also wouldn't validate in the "else" CRC calculation where type is included - crc = CRC16.ccitt(buffer + 3, size - 3); - - if (buffer[1] != ((crc >> 8) & 0xFF) || - buffer[2] != (crc & 0xFF)) - return; - } else { - // Normal, fixed length packet, where the CRC is the last member - crc = CRC16.ccitt(buffer, size - 2); + uint16_t crc = CRC16.ccitt(buffer, size - 2); - if (buffer[size - 1] != ((crc >> 8) & 0xFF) || - buffer[size - 2] != (crc & 0xFF)) - return; - } + if (buffer[size - 1] != ((crc >> 8) & 0xFF) || + buffer[size - 2] != (crc & 0xFF)) + return; if (buffer[0] == PACKET_ID_LL_HEARTBEAT && size == sizeof(struct ll_heartbeat)) { @@ -620,40 +592,27 @@ void onPacketReceived(const uint8_t *buffer, size_t size) { } else if (buffer[0] == PACKET_ID_LL_HIGH_LEVEL_STATE && size == sizeof(struct ll_high_level_state)) { // copy the state last_high_level_state = *((struct ll_high_level_state *) buffer); - } else if ((buffer[0] == PACKET_ID_LL_HIGH_LEVEL_CONFIG_REQ || buffer[0] == PACKET_ID_LL_HIGH_LEVEL_CONFIG_RSP) && - (size == sizeof(struct ll_high_level_config) || size == sizeof(struct ll_high_level_config) + sizeof(struct ll_high_level_config_ext_v2))) { - // Read and handle received config - struct ll_high_level_config *pkt = (struct ll_high_level_config *)buffer; - // Lower comms_version is leading - pkt->comms_version <= LL_HIGH_LEVEL_CONFIG_MAX_COMMS_VERSION ? comms_version = pkt->comms_version : comms_version = LL_HIGH_LEVEL_CONFIG_MAX_COMMS_VERSION; - config_bitmask = pkt->config_bitmask; // Take over as sent. HL is leading (for now) + } else if (buffer[0] == PACKET_ID_LL_HIGH_LEVEL_CONFIG_REQ || buffer[0] == PACKET_ID_LL_HIGH_LEVEL_CONFIG_RSP) { + // This is a flexible length package where the size may vary when ll_high_level_config struct got enhanced only on one side. + // If payload size is larger than our struct size, ensure that we only copy those we know of = our struct size. + // If payload size is smaller than our struct size, copy only the payload we got, but ensure that the unsent member(s) have reasonable defaults. + size_t payload_size = min(sizeof(ll_high_level_config), size - 3); // -1 type -2 crc - // PR-80: Assign volume & language if not already stored in flash-config + // Use a temporary config for easier sanity adaption and copy our live config, which has at least reasonable defaults. + // The live config copy ensures that we've reasonable values for the case that HL config struct is older than ours. + ll_high_level_config tmp_config = llhl_config; - // Handle possible ll_high_level_config_ext_v2 extension - if (comms_version >= 2) { - // Read and handle extension v2 - struct ll_high_level_config_ext_v2 *pkt = (struct ll_high_level_config_ext_v2 *)buffer + sizeof(struct ll_high_level_config); - - // Fix exceed of absolute max. values - pkt->v_charge_max = min(pkt->v_charge_max, V_CHARGE_ABS_MAX); - pkt->i_charge_max = min(pkt->i_charge_max, I_CHARGE_ABS_MAX); - - // Copy extension packet to config_v2 - config_v2 = *((struct ll_high_level_config_ext_v2 *)buffer + sizeof(struct ll_high_level_config)); - - // TODO: Parse hall config fields and build a compact iterable vector/array/... of active hall inputs or do it directly in updateEmergency() - - // TODO: Decide which fields should get stored in nv_config (flash) so that it's directly avail after power-up (without the need of ros_running) - // My current thoughts are: - // v_charge_max for those who need a much lower or higher charging voltage, so that battery doesn't get empty or overload if ROS is offline for a longer period (or silently crashed) - // i_charge is similar. If one has a higher current DCDC and dock his empty mower, it should charge, even if ROS is down - // v_battery_max for sure (overcharge protection) - // - // but NOT: - // halls_config/inverted? Think we should always start with default OM halls config but if comms_version >= 2, wait till v2 packet extension got received. - // tilt/lift periods - } + // Copy payload to temporary config (behind type) + memcpy(&tmp_config, buffer + 1, payload_size); + + // Sanity + tmp_config.v_charge_max = min(tmp_config.v_charge_max, V_CHARGE_ABS_MAX); // Fix exceed of hardware limits + tmp_config.i_charge_max = min(tmp_config.i_charge_max, I_CHARGE_ABS_MAX); // Fix exceed of hardware limits + + // Make config live + llhl_config = tmp_config; + + // PR-80: Assign volume & language if not already stored in flash-config if (buffer[0] == PACKET_ID_LL_HIGH_LEVEL_CONFIG_REQ) sendConfigMessage(PACKET_ID_LL_HIGH_LEVEL_CONFIG_RSP); @@ -662,7 +621,7 @@ void onPacketReceived(const uint8_t *buffer, size_t size) { // returns true, if it's a good idea to charge the battery (current, voltages, ...) bool checkShouldCharge() { - return status_message.v_charge < config_v2.v_charge_max && status_message.charging_current < config_v2.i_charge_max && status_message.v_battery < config_v2.v_battery_max; + return status_message.v_charge < llhl_config.v_charge_max && status_message.charging_current < llhl_config.i_charge_max && status_message.v_battery < llhl_config.v_battery_max; } void updateChargingEnabled() { From 9a50a0537e9617fadcdbace86a8d102cc0a757e1 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?J=C3=B6rg=20Ebeling?= Date: Fri, 11 Oct 2024 21:13:22 +0200 Subject: [PATCH 05/32] Cleanup, add and rename config struct member --- Firmware/LowLevel/include/config.h | 6 ++++++ Firmware/LowLevel/src/datatypes.h | 29 ++++++++++++++++++----------- Firmware/LowLevel/src/main.cpp | 16 +++++----------- 3 files changed, 29 insertions(+), 22 deletions(-) diff --git a/Firmware/LowLevel/include/config.h b/Firmware/LowLevel/include/config.h index fca0cf56..628285fb 100644 --- a/Firmware/LowLevel/include/config.h +++ b/Firmware/LowLevel/include/config.h @@ -1,6 +1,12 @@ #ifndef _CONFIG_H #define _CONFIG_H +#define BATT_ABS_MAX 28.7f +#define BATT_ABS_Min 21.7f + +#define BATT_FULL BATT_ABS_MAX - 0.3f +#define BATT_EMPTY BATT_ABS_Min + 0.3f + #define TILT_EMERGENCY_MILLIS 2500 // Time for a single wheel to be lifted in order to count as emergency (0 disable). This is to filter uneven ground. #define LIFT_EMERGENCY_MILLIS 100 // Time for both wheels to be lifted in order to count as emergency (0 disable). This is to filter uneven ground. diff --git a/Firmware/LowLevel/src/datatypes.h b/Firmware/LowLevel/src/datatypes.h index e58ec351..9ded81a2 100644 --- a/Firmware/LowLevel/src/datatypes.h +++ b/Firmware/LowLevel/src/datatypes.h @@ -164,28 +164,35 @@ struct HallConfig { #define MAX_HALL_INPUTS 10 // How much Hall-inputs we support. 4 * OM + 6 * Stock-CoverUI + 0 spare (because not yet required to make it fixed) -// LL/HL config packet, encapsulated in wire_msg for transfer, bi-directional, flexible-length, with defaults for YF-C500. +// LL/HL config packet, bi-directional, flexible-length, with defaults for YF-C500. #pragma pack(push, 1) struct ll_high_level_config { // ATTENTION: This is a flexible length struct. It is allowed to grow independently to HL without loosing compatibility, // but never change or restructure already published member, except you really know their consequences. - uint8_t comms_version = 1; // Transitional comms_version, can safely renamed as spare for other use in, let's say 2025 ;-) + + // uint8_t type; Just for illustration. Get set in wire buffer with type PACKET_ID_LL_HIGH_LEVEL_CONFIG_REQ or PACKET_ID_LL_HIGH_LEVEL_CONFIG_RSP + uint8_t config_bitmask = 0; // See LL_HIGH_LEVEL_CONFIG_BIT_* - int8_t volume = 80; // Volume (0-100%) feedback (if directly changed via CoverUI) - iso639_1 language = {'e', 'n'}; // ISO 639-1 (2-char) language code (en, de, ...) - float v_charge_max = V_CHARGE_MAX; // Max. charging voltage before charging get switched off - float i_charge_max = I_CHARGE_MAX; // Max. charging current before charging get switched off - float v_battery_max = 29.0f; // Max. battery voltage before charging get switched off + uint16_t rain_threshold = 700; // If (stock CoverUI) rain value < rain_threshold then it rains. Expected to differ between C500, SA and SC types + float v_charge_cutoff = V_CHARGE_MAX; // Protective max. charging voltage before charging get switched off + float i_charge_cutoff = I_CHARGE_MAX; // Protective max. charging current before charging get switched off + float v_battery_cutoff = 29.0f; // Protective max. battery voltage before charging get switched off + float v_battery_empty = BATT_EMPTY; // Empty battery voltage used for % calc of capacity + float v_battery_full = BATT_FULL; // Full battery voltage used for % calc of capacity uint16_t lift_period = LIFT_EMERGENCY_MILLIS; // Period (ms) for both wheels to be lifted in order to count as emergency (0 disable, 0xFFFF do not change). This is to filter uneven ground uint16_t tilt_period = TILT_EMERGENCY_MILLIS; // Period (ms) for a single wheel to be lifted in order to count as emergency (0 disable, 0xFFFF do not change). This is to filter uneven ground + iso639_1 language = {'e', 'n'}; // ISO 639-1 (2-char) language code (en, de, ...) + int8_t volume = 80; // Volume (0-100%) feedback (if directly changed i.e. via CoverUI or WebApp) HallConfig hall_configs[MAX_HALL_INPUTS] = { - {HallMode::emergency, HallLevel::activeLow}, // [0] OM Hall-1 input - {HallMode::emergency, HallLevel::activeLow}, // [1] OM Hall-2 input - {HallMode::stop, HallLevel::activeLow}, // [2] OM Hall-3 input - {HallMode::stop, HallLevel::activeLow}, // [3] OM Hall-4 input + {HallMode::emergency, HallLevel::activeLow}, // [0] OM Hall-1 input (Lift1) + {HallMode::emergency, HallLevel::activeLow}, // [1] OM Hall-2 input (Lift2) + {HallMode::stop, HallLevel::activeLow}, // [2] OM Hall-3 input (Stop1) + {HallMode::stop, HallLevel::activeLow}, // [3] OM Hall-4 input (Stop2) // [4] Stock-CoverUI-1 ... [9] Stock-CoverUI-6 defaults to off }; // INFO: Before adding a new member here: Decide if and how much hall_configs spares do we like to have + + // uint16_t crc; Just for illustration, that it get appended, but only within the wire buffer } __attribute__((packed)); #pragma pack(pop) diff --git a/Firmware/LowLevel/src/main.cpp b/Firmware/LowLevel/src/main.cpp index 17ea9a9a..6323e350 100644 --- a/Firmware/LowLevel/src/main.cpp +++ b/Firmware/LowLevel/src/main.cpp @@ -63,12 +63,6 @@ SerialPIO uiSerial(PIN_UI_TX, PIN_UI_RX, 250); #define R_SHUNT 0.003f #define CURRENT_SENSE_GAIN 100.0f -#define BATT_ABS_MAX 28.7f -#define BATT_ABS_Min 21.7f - -#define BATT_FULL BATT_ABS_MAX - 0.3f -#define BATT_EMPTY BATT_ABS_Min + 0.3f - // Emergency will be engaged, if no heartbeat was received in this time frame. #define HEARTBEAT_MILLIS 500 @@ -599,15 +593,15 @@ void onPacketReceived(const uint8_t *buffer, size_t size) { size_t payload_size = min(sizeof(ll_high_level_config), size - 3); // -1 type -2 crc // Use a temporary config for easier sanity adaption and copy our live config, which has at least reasonable defaults. - // The live config copy ensures that we've reasonable values for the case that HL config struct is older than ours. - ll_high_level_config tmp_config = llhl_config; + // The live config copy ensures that we've reasonable values for the case that HL config struct is older (smaller) than ours. + auto tmp_config = llhl_config; // Copy payload to temporary config (behind type) memcpy(&tmp_config, buffer + 1, payload_size); // Sanity - tmp_config.v_charge_max = min(tmp_config.v_charge_max, V_CHARGE_ABS_MAX); // Fix exceed of hardware limits - tmp_config.i_charge_max = min(tmp_config.i_charge_max, I_CHARGE_ABS_MAX); // Fix exceed of hardware limits + tmp_config.v_charge_cutoff = min(tmp_config.v_charge_cutoff, V_CHARGE_ABS_MAX); // Fix exceed of hardware limits + tmp_config.i_charge_cutoff = min(tmp_config.i_charge_cutoff, I_CHARGE_ABS_MAX); // Fix exceed of hardware limits // Make config live llhl_config = tmp_config; @@ -621,7 +615,7 @@ void onPacketReceived(const uint8_t *buffer, size_t size) { // returns true, if it's a good idea to charge the battery (current, voltages, ...) bool checkShouldCharge() { - return status_message.v_charge < llhl_config.v_charge_max && status_message.charging_current < llhl_config.i_charge_max && status_message.v_battery < llhl_config.v_battery_max; + return status_message.v_charge < llhl_config.v_charge_cutoff && status_message.charging_current < llhl_config.i_charge_cutoff && status_message.v_battery < llhl_config.v_battery_cutoff; } void updateChargingEnabled() { From 13aff7f03ca256ed13c18a654835da840b8dd7cf Mon Sep 17 00:00:00 2001 From: Robert Vollmer Date: Fri, 11 Oct 2024 23:02:52 +0200 Subject: [PATCH 06/32] refactor: create applyConfig() --- Firmware/LowLevel/src/main.cpp | 44 ++++++++++++++++++---------------- 1 file changed, 24 insertions(+), 20 deletions(-) diff --git a/Firmware/LowLevel/src/main.cpp b/Firmware/LowLevel/src/main.cpp index 6323e350..0513b2fa 100644 --- a/Firmware/LowLevel/src/main.cpp +++ b/Firmware/LowLevel/src/main.cpp @@ -552,6 +552,29 @@ void sendConfigMessage(uint8_t pkt_type) { free(msg); } +void applyConfig(const uint8_t *buffer, size_t size) { + // This is a flexible length package where the size may vary when ll_high_level_config struct got enhanced only on one side. + // If payload size is larger than our struct size, ensure that we only copy those we know of = our struct size. + // If payload size is smaller than our struct size, copy only the payload we got, but ensure that the unsent member(s) have reasonable defaults. + size_t payload_size = min(sizeof(ll_high_level_config), size - 2); // exclude crc + + // Use a temporary config for easier sanity adaption and copy our live config, which has at least reasonable defaults. + // The live config copy ensures that we've reasonable values for the case that HL config struct is older (smaller) than ours. + auto tmp_config = llhl_config; + + // Copy payload to temporary config + memcpy(&tmp_config, buffer, payload_size); + + // Sanity + tmp_config.v_charge_cutoff = min(tmp_config.v_charge_cutoff, V_CHARGE_ABS_MAX); // Fix exceed of hardware limits + tmp_config.i_charge_cutoff = min(tmp_config.i_charge_cutoff, I_CHARGE_ABS_MAX); // Fix exceed of hardware limits + + // Make config live + llhl_config = tmp_config; + + // PR-80: Assign volume & language if not already stored in flash-config +} + void onPacketReceived(const uint8_t *buffer, size_t size) { // sanity check for CRC to work (1 type, 1 data, 2 CRC) if (size < 4) @@ -587,26 +610,7 @@ void onPacketReceived(const uint8_t *buffer, size_t size) { // copy the state last_high_level_state = *((struct ll_high_level_state *) buffer); } else if (buffer[0] == PACKET_ID_LL_HIGH_LEVEL_CONFIG_REQ || buffer[0] == PACKET_ID_LL_HIGH_LEVEL_CONFIG_RSP) { - // This is a flexible length package where the size may vary when ll_high_level_config struct got enhanced only on one side. - // If payload size is larger than our struct size, ensure that we only copy those we know of = our struct size. - // If payload size is smaller than our struct size, copy only the payload we got, but ensure that the unsent member(s) have reasonable defaults. - size_t payload_size = min(sizeof(ll_high_level_config), size - 3); // -1 type -2 crc - - // Use a temporary config for easier sanity adaption and copy our live config, which has at least reasonable defaults. - // The live config copy ensures that we've reasonable values for the case that HL config struct is older (smaller) than ours. - auto tmp_config = llhl_config; - - // Copy payload to temporary config (behind type) - memcpy(&tmp_config, buffer + 1, payload_size); - - // Sanity - tmp_config.v_charge_cutoff = min(tmp_config.v_charge_cutoff, V_CHARGE_ABS_MAX); // Fix exceed of hardware limits - tmp_config.i_charge_cutoff = min(tmp_config.i_charge_cutoff, I_CHARGE_ABS_MAX); // Fix exceed of hardware limits - - // Make config live - llhl_config = tmp_config; - - // PR-80: Assign volume & language if not already stored in flash-config + applyConfig(buffer + 1, size - 1); // Skip type if (buffer[0] == PACKET_ID_LL_HIGH_LEVEL_CONFIG_REQ) sendConfigMessage(PACKET_ID_LL_HIGH_LEVEL_CONFIG_RSP); From 1c0cfacb801e5e21bd3c39f4b6be79a5c9e25708 Mon Sep 17 00:00:00 2001 From: Robert Vollmer Date: Fri, 11 Oct 2024 23:10:30 +0200 Subject: [PATCH 07/32] PoC for LittleFS --- Firmware/LowLevel/include/nv_config.h | 84 ------------ Firmware/LowLevel/platformio.ini | 1 + Firmware/LowLevel/src/main.cpp | 50 ++++++- Firmware/LowLevel/src/nv_config.cpp | 181 -------------------------- 4 files changed, 49 insertions(+), 267 deletions(-) delete mode 100644 Firmware/LowLevel/include/nv_config.h delete mode 100644 Firmware/LowLevel/src/nv_config.cpp diff --git a/Firmware/LowLevel/include/nv_config.h b/Firmware/LowLevel/include/nv_config.h deleted file mode 100644 index 4a8f57c1..00000000 --- a/Firmware/LowLevel/include/nv_config.h +++ /dev/null @@ -1,84 +0,0 @@ -/* - * Copyright 2024 Jörg Ebeling (Apehaenger) - * - * Permission is hereby granted, free of charge, to any person obtaining a copy - * of this software and associated documentation files (the "Software"), to deal - * in the Software without restriction, including without limitation the rights - * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - * copies of the Software, and to permit persons to whom the Software is - * furnished to do so, subject to the following conditions: - * - * The above copyright notice and this permission notice shall be included in all - * copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE - * SOFTWARE.* Testing/examples for reading/writing flash on the RP2040. - * - * Heavily inspired, copied from, as well as must-read: - * https://github.com/MakerMatrix/RP2040_flash_programming - */ - -#ifndef _NV_CONFIG_H -#define _NV_CONFIG_H - -#include - -#ifdef ENABLE_SOUND_MODULE -#include "soundsystem.h" -#else -#define VOLUME_DEFAULT 80 -#endif - -#define VOLUME_DEFAULT 80 // FIXME: Backported from PR-80 - -#include "../src/datatypes.h" - -#define NV_CONFIG_MAX_SAVE_INTERVAL 60000UL // Don't save more often than once a minute - -// config_bitmask. Don't mistake with LL_HIGH_LEVEL_CONFIG_BIT. Similar, but not mandatory equal! -#define NV_CONFIG_BIT_DFPIS5V 1 << 0 // DFP is set to 5V - -#define NV_RECORD_ID 0x4F4D4331 // Record struct identifier "OMC1" for future flexible length Record.config -#define NV_RECORD_ALIGNMENT (_Alignof(uint32_t)) // Ptr alignment of Record.id for quick in memory access - -namespace nv_config { -#pragma pack(push, 1) -// This is where our application values should go. -// It's possible to extended it, but any extension should add an extension related CRC so that an old/last stored Record.config isn't lost. -// (a new extension-crc isn't valid with a old Record.config. Thus the new extension values may get set i.e. with default values) -struct Config { - // Config bitmask: - // Bit 0: DFP is 5V (enable full sound). See NV_CONFIG_BIT_DFPIS5V - uint8_t config_bitmask = 0; // Don't mistake with LL_HIGH_LEVEL_CONFIG_BIT. Similar, but not mandatory equal! - uint8_t volume = VOLUME_DEFAULT; // Sound volume (0-100%) - iso639_1 language = {'e', 'n'}; // Default to 'en' - uint32_t rain_threshold = 700; // If (stock CoverUI) rain value < rain_threshold then it rains. Expected to differ between C500, SA and SC types - - /* Possible future config settings - uint16_t free; // Future config setting - uint16_t free_n; // Future config setting - uint16_t crc_n; // Future config CRC16 (for the new member) for detection if loaded (possibly old) config already has the new member */ -} __attribute__((packed)); - -// Record(s) get placed sequentially into a flash page. -// The Record structure shouldn't get changed, because it would make old flash Record's unusable. Instead of, change Record.config -struct Record { - const uint32_t id = NV_RECORD_ID; // Fixed record identifier, used to identify a possible Record within a flash page. If width get changed, change also NV_RECORD_ALIGNMENT - uint32_t num_sector_erase = 0; // For wear level stats - uint32_t num_page_write = 0; // For informational purposes - uint16_t crc; // Required to ensure that a found NV_RECORD_ID is really a Record - Config config; -} __attribute__((packed)); -#pragma pack(pop) - -Config *get(); // Returned Config pointer hold the data of the last saved Record.config, or a default one. Config member are writable, see delayedSaveChanges() -void delayedSaveChanges(); // Handle a possible changed nv_config::config member and save it to flash, but only within NV_CONFIG_MAX_SAVE_INTERVAL timeout for wear level protection - -} // namespace nv_config - -#endif // _NV_CONFIG_H \ No newline at end of file diff --git a/Firmware/LowLevel/platformio.ini b/Firmware/LowLevel/platformio.ini index 8fcaa171..4ae1fba1 100644 --- a/Firmware/LowLevel/platformio.ini +++ b/Firmware/LowLevel/platformio.ini @@ -23,6 +23,7 @@ lib_deps = Wire SPI FastCRC + LittleFS bakercp/PacketSerial@^1.4.0 powerbroker2/FireTimer@^1.0.5 https://github.com/ClemensElflein/NeoPixelConnect.git diff --git a/Firmware/LowLevel/src/main.cpp b/Firmware/LowLevel/src/main.cpp index 0513b2fa..4b5edc38 100644 --- a/Firmware/LowLevel/src/main.cpp +++ b/Firmware/LowLevel/src/main.cpp @@ -24,7 +24,7 @@ #include "ui_board.h" #include "imu.h" #include "debug.h" -#include "nv_config.h" +#include #ifdef ENABLE_SOUND_MODULE #include @@ -119,13 +119,15 @@ uint8_t ui_topic_bitmask = Topic_set_leds; // UI subscription, default to Set_LE uint16_t ui_interval = 1000; // UI send msg (LED/State) interval (ms) struct ll_high_level_config llhl_config; // LL/HL configuration (is initialized with YF-C500 defaults) -nv_config::Config *nv_cfg; // Non-volatile configuration +const String CONFIG_FILENAME = "/openmower.cfg"; void sendMessage(void *message, size_t size); void sendUIMessage(void *message, size_t size); void onPacketReceived(const uint8_t *buffer, size_t size); void onUIPacketReceived(const uint8_t *buffer, size_t size); void manageUISubscriptions(); +void saveConfigToFlash(); +void readConfigFromFlash(); void setRaspiPower(bool power) { // Update status bits in the status message @@ -418,6 +420,10 @@ void setup() { UISerial.setStream(&UI1_SERIAL); UISerial.setPacketHandler(&onUIPacketReceived); + // Initialize flash and try to read config + LittleFS.begin(); + readConfigFromFlash(); + /* * IMU INITIALIZATION */ @@ -612,6 +618,9 @@ void onPacketReceived(const uint8_t *buffer, size_t size) { } else if (buffer[0] == PACKET_ID_LL_HIGH_LEVEL_CONFIG_REQ || buffer[0] == PACKET_ID_LL_HIGH_LEVEL_CONFIG_RSP) { applyConfig(buffer + 1, size - 1); // Skip type + // Store in flash + saveConfigToFlash(); + if (buffer[0] == PACKET_ID_LL_HIGH_LEVEL_CONFIG_REQ) sendConfigMessage(PACKET_ID_LL_HIGH_LEVEL_CONFIG_RSP); } @@ -800,3 +809,40 @@ void sendUIMessage(void *message, size_t size) { UISerial.send((uint8_t *) message, size); } + +void saveConfigToFlash() { + uint16_t crc = CRC16.ccitt((const uint8_t*) &llhl_config, sizeof(llhl_config)); + // TODO: Return early if CRC is unchanged to avoid flash wear. + + File f = LittleFS.open(CONFIG_FILENAME, "w"); + f.write((const uint8_t*) &llhl_config, sizeof(llhl_config)); + f.write((const uint8_t*) &crc, 2); + f.close(); +} + +void readConfigFromFlash() { + File f = LittleFS.open(CONFIG_FILENAME, "r"); + if (!f) return; + + // sanity check for CRC to work (1 data, 2 CRC) + const size_t size = f.size(); + if (size < 3) { + f.close(); + return; + } + + // read config + uint8_t *buffer = (uint8_t *)malloc(f.size()); + f.read(buffer, size); + f.close(); + + // check the CRC + uint16_t crc = CRC16.ccitt(buffer, size - 2); + + if (buffer[size - 1] != ((crc >> 8) & 0xFF) || + buffer[size - 2] != (crc & 0xFF)) + return; + + applyConfig(buffer, size); + free(buffer); +} diff --git a/Firmware/LowLevel/src/nv_config.cpp b/Firmware/LowLevel/src/nv_config.cpp deleted file mode 100644 index 054e9381..00000000 --- a/Firmware/LowLevel/src/nv_config.cpp +++ /dev/null @@ -1,181 +0,0 @@ -/* - * Copyright 2024 Jörg Ebeling (Apehaenger) - * - * Permission is hereby granted, free of charge, to any person obtaining a copy - * of this software and associated documentation files (the "Software"), to deal - * in the Software without restriction, including without limitation the rights - * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - * copies of the Software, and to permit persons to whom the Software is - * furnished to do so, subject to the following conditions: - * - * The above copyright notice and this permission notice shall be included in all - * copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE - * SOFTWARE.* Testing/examples for reading/writing flash on the RP2040. - * - * Heavily inspired, copied from, as well as must-read: - * https://github.com/MakerMatrix/RP2040_flash_programming - */ -#include "nv_config.h" - -#include - -#include - -#include "debug.h" - -extern "C" { -#include -#include -}; - -#define FLASH_TARGET_OFFSET (PICO_FLASH_SIZE_BYTES - FLASH_SECTOR_SIZE) // Target offset to the last sector of flash -#define NV_MIN_RECORD_SIZE (sizeof(Record) - sizeof(Config)) // Minimum Record size (Record size without Config member) -#define NV_PAGES_IN_SECTOR (FLASH_SECTOR_SIZE / FLASH_PAGE_SIZE) // How much pages fit into one sector -#define NV_RECORD_CRC_DATALEN (sizeof(Record) - sizeof(Config) - sizeof(cur_record.crc)) - -#ifdef DEBUG_PREFIX -#undef DEBUG_PREFIX -#define DEBUG_PREFIX "[NVC] " -#endif - -namespace nv_config { -static_assert(sizeof(Record) <= FLASH_PAGE_SIZE, "Record struct size larger than page size"); - -int first_empty_page = -1; // First empty page in sector -int last_used_page = -1; // Last used page with non-empty data -int last_record_pos = -1; // Last record position within page (page_buf) - -uint8_t page_buf[FLASH_PAGE_SIZE]; // Page buffer required for subsequential flash_range_program() of the same page -Record cur_record; // Current (last or (if there hasn't been a Record flashed before) default) Record -uint16_t config_crc; // CRC of current Record->config used for config change detection - -FastCRC16 CRC16; - -unsigned long next_save_millis = millis() + NV_CONFIG_MAX_SAVE_INTERVAL; - -Config *get() { - DEBUG_PRINTF("FLASH_PAGE_SIZE: %d, FLASH_SECTOR_SIZE: %d, FLASH_BLOCK_SIZE: %d, PICO_FLASH_SIZE_BYTES: %d, XIP_BASE: 0x%x, FLASH_TARGET_OFFSET: %d\n", - FLASH_PAGE_SIZE, FLASH_SECTOR_SIZE, FLASH_BLOCK_SIZE, PICO_FLASH_SIZE_BYTES, XIP_BASE, FLASH_TARGET_OFFSET); - DEBUG_PRINTF("NV_PAGES_IN_SECTOR: %d, sizeof(Record): %d, sizeof(Config): %d, possible num of records within one page: %d\n", - NV_PAGES_IN_SECTOR, sizeof(Record), sizeof(Config), FLASH_PAGE_SIZE / sizeof(Record)); - - // Read flash until first empty page found - int addr; - unsigned int page; - int32_t *p; - for (page = 0; page < FLASH_SECTOR_SIZE / FLASH_PAGE_SIZE; page++) { - p = (int32_t *)(XIP_BASE + FLASH_TARGET_OFFSET + (page * FLASH_PAGE_SIZE)); - - // 0xFFFFFFFF cast as an int is -1 so this is how we detect an empty page - DEBUG_PRINTF("Page %d (0x%x): record_id = %ld (0x%lx)\n", page, int(p), *p, *p); - if (*p == -1 && first_empty_page < 0) { - first_empty_page = page; - break; - } - last_used_page = page; - } - DEBUG_PRINTF("last_used_page %d, first_empty_page %d\n", last_used_page, first_empty_page); - - // Find last written Record - if (last_used_page >= 0) { - // RLoop over last_used_page to find latest record via it's record.id - DEBUG_PRINTF("Last possible record (unaligned) = FLASH_PAGE_SIZE %d - NV_MIN_RECORD_SIZE %d = %u\n", FLASH_PAGE_SIZE, NV_MIN_RECORD_SIZE, FLASH_PAGE_SIZE - NV_MIN_RECORD_SIZE); - int addr = XIP_BASE + FLASH_TARGET_OFFSET + (last_used_page * FLASH_PAGE_SIZE); - // Calc last possible record offset without config, for the case that Record.config get changed, and pointer-align to "next multiple of" - int last_possible_record_offset = (FLASH_PAGE_SIZE - NV_MIN_RECORD_SIZE) - ((FLASH_PAGE_SIZE - NV_MIN_RECORD_SIZE) % NV_RECORD_ALIGNMENT) + NV_RECORD_ALIGNMENT; - DEBUG_PRINTF("last_possible_record_offset (aligned) 0x%x for Record.id alignment of %d\n", last_possible_record_offset, NV_RECORD_ALIGNMENT); - // Record test_record; - for (size_t i = last_possible_record_offset; i >= 0; i = i - NV_RECORD_ALIGNMENT) { - uint32_t *p = (uint32_t *)(addr + i); - if (*p != NV_RECORD_ID) - continue; - - // Validate if the found NV_RECORD_ID is a valid Record.id - DEBUG_PRINTF("Page %d, offset 0x%x (at %p): Record.id prospect = 0x%lx\n", last_used_page, i, p, *p); - Record test_record; - memcpy(&test_record, (uint8_t *)p, sizeof(Record)); - DEBUG_PRINTF("Test- Record: num_sector_erase: %ld, num_page_write: %ld, crc: 0x%lx\n", test_record.num_sector_erase, test_record.num_page_write, test_record.crc); - uint16_t test_crc = CRC16.ccitt((uint8_t *)&test_record, NV_RECORD_CRC_DATALEN); - DEBUG_PRINTF("Test- Record CRC 0x%x of datalen %d\n", test_crc, NV_RECORD_CRC_DATALEN); - if (test_crc != test_record.crc) - continue; - - DEBUG_PRINTF("Test- Record is valid. Buffer the full flash page\n"); - memcpy(&page_buf, (uint8_t *)addr, FLASH_PAGE_SIZE); - memcpy(&cur_record, &test_record, sizeof(Record)); - last_record_pos = i; - break; - } - } - DEBUG_PRINTF("Last (or default) config's volume: %d\n", cur_record.config.volume); - - // CRC for simple checking if config has changed - config_crc = CRC16.ccitt((uint8_t *)&cur_record.config, sizeof(Config)); - DEBUG_PRINTF("cur_record.config CRC: 0x%x\n", config_crc); - - return &cur_record.config; -} - -void delayedSaveChanges() { - // Wear level protection - if (millis() < next_save_millis) - return; - next_save_millis = millis() + NV_CONFIG_MAX_SAVE_INTERVAL; - - // Check CRC if config changed - uint16_t check_crc = CRC16.ccitt((uint8_t *)&cur_record.config, sizeof(Config)); - DEBUG_PRINTF("Actual- vs. stored- config CRC: 0x%x ?= 0x%x\n", check_crc, config_crc); - if (check_crc == config_crc) - return; // Record.config doesn't changed - - // Prepare record position within page buffer - if (last_record_pos == -1) - last_record_pos = 0; - else { - last_record_pos += sizeof(Record); - last_record_pos = last_record_pos - (last_record_pos % NV_RECORD_ALIGNMENT) + NV_RECORD_ALIGNMENT; // Adjust to "next multiple of" NV_RECORD_ALIGNMENT - } - if ((last_record_pos + sizeof(Record)) > FLASH_PAGE_SIZE) { - // Will not fit into the current page anymore - last_used_page++; - last_record_pos = 0; - first_empty_page++; - std::fill_n(page_buf, FLASH_PAGE_SIZE, 0xff); // Mark page buffer as (flash) erased - } - - // If no empty page got found during get(), or last page got eaten, let's erase our flash sector - if (first_empty_page < 0 || last_used_page >= NV_PAGES_IN_SECTOR) { - DEBUG_PRINTF("Full sector, erase...\n"); - uint32_t ints = save_and_disable_interrupts(); - flash_range_erase(FLASH_TARGET_OFFSET, FLASH_SECTOR_SIZE); - restore_interrupts(ints); - // Reset positioning vars - last_used_page = 0; - first_empty_page = 0; - cur_record.num_sector_erase++; - std::fill_n(page_buf, FLASH_PAGE_SIZE, 0xff); // Mark page buffer as (flash) erased - } - - // Prepare record - cur_record.num_page_write++; - cur_record.crc = CRC16.ccitt((uint8_t *)&cur_record, NV_RECORD_CRC_DATALEN); - DEBUG_PRINTF("Record CRC 0x%x of datalen %d\n", cur_record.crc, NV_RECORD_CRC_DATALEN); - - // memcopy cur_record to page buffer - memcpy(&page_buf[last_record_pos], &cur_record, sizeof(Record)); - - // Write page to flash - DEBUG_PRINTF("Write to page %d, with new record pos %d: volume %d...\n", last_used_page, last_record_pos, cur_record.config.volume); - uint32_t ints = save_and_disable_interrupts(); - flash_range_program(FLASH_TARGET_OFFSET + (last_used_page * FLASH_PAGE_SIZE), (uint8_t *)page_buf, sizeof(page_buf)); - restore_interrupts(ints); - config_crc = check_crc; // Update last saved config CRC -} -} // namespace nv_config \ No newline at end of file From 68ed301c3fe198133c7fe683d806ce9b0749ca73 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?J=C3=B6rg=20Ebeling?= Date: Fri, 11 Oct 2024 23:32:51 +0200 Subject: [PATCH 08/32] Implement review hints of rovo89 --- Firmware/LowLevel/include/config.h | 6 ++++-- Firmware/LowLevel/include/debug.h | 5 ----- Firmware/LowLevel/src/datatypes.h | 8 ++++---- Firmware/LowLevel/src/main.cpp | 2 +- 4 files changed, 9 insertions(+), 12 deletions(-) diff --git a/Firmware/LowLevel/include/config.h b/Firmware/LowLevel/include/config.h index 628285fb..b9bf625b 100644 --- a/Firmware/LowLevel/include/config.h +++ b/Firmware/LowLevel/include/config.h @@ -2,10 +2,12 @@ #define _CONFIG_H #define BATT_ABS_MAX 28.7f -#define BATT_ABS_Min 21.7f +#define BATT_ABS_MIN 21.7f +#define BATT_EMPTY BATT_ABS_MIN + 0.3f #define BATT_FULL BATT_ABS_MAX - 0.3f -#define BATT_EMPTY BATT_ABS_Min + 0.3f + +#define V_BATT_CUTOFF 29.0f #define TILT_EMERGENCY_MILLIS 2500 // Time for a single wheel to be lifted in order to count as emergency (0 disable). This is to filter uneven ground. #define LIFT_EMERGENCY_MILLIS 100 // Time for both wheels to be lifted in order to count as emergency (0 disable). This is to filter uneven ground. diff --git a/Firmware/LowLevel/include/debug.h b/Firmware/LowLevel/include/debug.h index 731f9641..407a0052 100644 --- a/Firmware/LowLevel/include/debug.h +++ b/Firmware/LowLevel/include/debug.h @@ -22,7 +22,6 @@ #ifdef USB_DEBUG #define DEBUG_SERIAL Serial -// #define DfMiniMp3Debug DEBUG_SERIAL // Also output DFPlayer IN/OUT cmd data // Some bloody simple debug macros which superfluous '#ifdef USB_DEBUG' ... #define DEBUG_BEGIN(b) \ @@ -39,9 +38,5 @@ #define DEBUG_PRINTF(fmt, ...) #endif -#define PRINTF_BINARY_PATTERN_INT8 "%c%c%c%c%c%c%c%c" -#define PRINTF_BYTE_TO_BINARY_INT8(i) \ - (((i)&0x80ll) ? '1' : '0'), (((i)&0x40ll) ? '1' : '0'), (((i)&0x20ll) ? '1' : '0'), (((i)&0x10ll) ? '1' : '0'), \ - (((i)&0x08ll) ? '1' : '0'), (((i)&0x04ll) ? '1' : '0'), (((i)&0x02ll) ? '1' : '0'), (((i)&0x01ll) ? '1' : '0') #endif // _DEBUG_H_ diff --git a/Firmware/LowLevel/src/datatypes.h b/Firmware/LowLevel/src/datatypes.h index 9ded81a2..769e22f3 100644 --- a/Firmware/LowLevel/src/datatypes.h +++ b/Firmware/LowLevel/src/datatypes.h @@ -144,9 +144,9 @@ typedef char iso639_1[2]; // Two char ISO 639-1 language code enum class HallMode : uint8_t { off = 0, - emergency, // lift & tilt - stop, - pause + emergency, // Triggers emergency with lift & tilt functionality + stop, // Stop mower + pause // Pause the mower (not yet implemented in ROS) }; // FIXME: Decide later which is more comfortable, activeLow = 0 | 1 @@ -176,7 +176,7 @@ struct ll_high_level_config { uint16_t rain_threshold = 700; // If (stock CoverUI) rain value < rain_threshold then it rains. Expected to differ between C500, SA and SC types float v_charge_cutoff = V_CHARGE_MAX; // Protective max. charging voltage before charging get switched off float i_charge_cutoff = I_CHARGE_MAX; // Protective max. charging current before charging get switched off - float v_battery_cutoff = 29.0f; // Protective max. battery voltage before charging get switched off + float v_battery_cutoff = V_BATT_CUTOFF; // Protective max. battery voltage before charging get switched off float v_battery_empty = BATT_EMPTY; // Empty battery voltage used for % calc of capacity float v_battery_full = BATT_FULL; // Full battery voltage used for % calc of capacity uint16_t lift_period = LIFT_EMERGENCY_MILLIS; // Period (ms) for both wheels to be lifted in order to count as emergency (0 disable, 0xFFFF do not change). This is to filter uneven ground diff --git a/Firmware/LowLevel/src/main.cpp b/Firmware/LowLevel/src/main.cpp index 6323e350..34188f6a 100644 --- a/Firmware/LowLevel/src/main.cpp +++ b/Firmware/LowLevel/src/main.cpp @@ -367,7 +367,7 @@ void setup() { rp2040.idleOtherCore(); #ifdef USB_DEBUG - DEBUG_SERIAL.begin(9600); + DEBUG_BEGIN(9600); #endif emergency_latch = true; From 1ff7d3181e6e85466d4faa70444a1be03dea20fa Mon Sep 17 00:00:00 2001 From: Robert Vollmer Date: Fri, 11 Oct 2024 23:33:19 +0200 Subject: [PATCH 09/32] Don't write config to flash if it hasn't changed --- Firmware/LowLevel/src/main.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/Firmware/LowLevel/src/main.cpp b/Firmware/LowLevel/src/main.cpp index 4b5edc38..6d113ea9 100644 --- a/Firmware/LowLevel/src/main.cpp +++ b/Firmware/LowLevel/src/main.cpp @@ -120,6 +120,7 @@ uint16_t ui_interval = 1000; // UI send msg (LED/State) interval ( struct ll_high_level_config llhl_config; // LL/HL configuration (is initialized with YF-C500 defaults) const String CONFIG_FILENAME = "/openmower.cfg"; +uint16_t config_crc_in_flash = 0; void sendMessage(void *message, size_t size); void sendUIMessage(void *message, size_t size); @@ -812,7 +813,7 @@ void sendUIMessage(void *message, size_t size) { void saveConfigToFlash() { uint16_t crc = CRC16.ccitt((const uint8_t*) &llhl_config, sizeof(llhl_config)); - // TODO: Return early if CRC is unchanged to avoid flash wear. + if (crc == config_crc_in_flash) return; File f = LittleFS.open(CONFIG_FILENAME, "w"); f.write((const uint8_t*) &llhl_config, sizeof(llhl_config)); @@ -843,6 +844,7 @@ void readConfigFromFlash() { buffer[size - 2] != (crc & 0xFF)) return; + config_crc_in_flash = crc; applyConfig(buffer, size); free(buffer); } From bca58265851c71ed20b73aa6ad2149989c26fe01 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?J=C3=B6rg=20Ebeling?= Date: Sat, 12 Oct 2024 00:51:01 +0200 Subject: [PATCH 10/32] Implement review hints of rovo89 --- .../include/{config.h => config_defaults.h} | 5 ++++ Firmware/LowLevel/src/datatypes.h | 28 +++++++++---------- Firmware/LowLevel/src/main.cpp | 4 +-- 3 files changed, 20 insertions(+), 17 deletions(-) rename Firmware/LowLevel/include/{config.h => config_defaults.h} (76%) diff --git a/Firmware/LowLevel/include/config.h b/Firmware/LowLevel/include/config_defaults.h similarity index 76% rename from Firmware/LowLevel/include/config.h rename to Firmware/LowLevel/include/config_defaults.h index b9bf625b..915bde0a 100644 --- a/Firmware/LowLevel/include/config.h +++ b/Firmware/LowLevel/include/config_defaults.h @@ -18,4 +18,9 @@ #define V_CHARGE_ABS_MAX 40.0f // Absolute max. limited by D2/D3 Schottky #define I_CHARGE_ABS_MAX 5.0f // Absolute max. limited by D2/D3 Schottky +#define RAIN_THRESHOLD 700U // (Yet) Stock-CoverUI exclusive raw ADC value. Is the measured value is lower, it rains + +#define SOUND_VOLUME 80 // Volume (0-100%) +#define LANGUAGE 'e', 'n' // ISO 639-1 (2-char) language code (en, de, ...) + #endif // _CONFIG_H \ No newline at end of file diff --git a/Firmware/LowLevel/src/datatypes.h b/Firmware/LowLevel/src/datatypes.h index 769e22f3..a985c5c6 100644 --- a/Firmware/LowLevel/src/datatypes.h +++ b/Firmware/LowLevel/src/datatypes.h @@ -19,7 +19,7 @@ #define _DATATYPES_H #include -#include "config.h" +#include "config_defaults.h" #define PACKET_ID_LL_STATUS 1 #define PACKET_ID_LL_IMU 2 @@ -143,16 +143,16 @@ struct ll_ui_event { typedef char iso639_1[2]; // Two char ISO 639-1 language code enum class HallMode : uint8_t { - off = 0, - emergency, // Triggers emergency with lift & tilt functionality - stop, // Stop mower - pause // Pause the mower (not yet implemented in ROS) + OFF = 0, + EMERGENCY, // Triggers emergency with lift & tilt functionality + STOP, // Stop mower + PAUSE // Pause the mower (not yet implemented in ROS) }; // FIXME: Decide later which is more comfortable, activeLow = 0 | 1 enum class HallLevel : uint8_t { - activeLow = 0, // If Hall-Sensor (or button) is active/triggered we've this level on our GPIO - activeHigh + ACTIVE_LOW = 0, // If Hall-Sensor (or button) is active/triggered we've this level on our GPIO + ACTIVE_HIGH }; #pragma pack(push, 1) @@ -173,7 +173,7 @@ struct ll_high_level_config { // uint8_t type; Just for illustration. Get set in wire buffer with type PACKET_ID_LL_HIGH_LEVEL_CONFIG_REQ or PACKET_ID_LL_HIGH_LEVEL_CONFIG_RSP uint8_t config_bitmask = 0; // See LL_HIGH_LEVEL_CONFIG_BIT_* - uint16_t rain_threshold = 700; // If (stock CoverUI) rain value < rain_threshold then it rains. Expected to differ between C500, SA and SC types + uint16_t rain_threshold = RAIN_THRESHOLD; // If (stock CoverUI) rain value < rain_threshold then it rains. Expected to differ between C500, SA and SC types float v_charge_cutoff = V_CHARGE_MAX; // Protective max. charging voltage before charging get switched off float i_charge_cutoff = I_CHARGE_MAX; // Protective max. charging current before charging get switched off float v_battery_cutoff = V_BATT_CUTOFF; // Protective max. battery voltage before charging get switched off @@ -181,13 +181,13 @@ struct ll_high_level_config { float v_battery_full = BATT_FULL; // Full battery voltage used for % calc of capacity uint16_t lift_period = LIFT_EMERGENCY_MILLIS; // Period (ms) for both wheels to be lifted in order to count as emergency (0 disable, 0xFFFF do not change). This is to filter uneven ground uint16_t tilt_period = TILT_EMERGENCY_MILLIS; // Period (ms) for a single wheel to be lifted in order to count as emergency (0 disable, 0xFFFF do not change). This is to filter uneven ground - iso639_1 language = {'e', 'n'}; // ISO 639-1 (2-char) language code (en, de, ...) - int8_t volume = 80; // Volume (0-100%) feedback (if directly changed i.e. via CoverUI or WebApp) + iso639_1 language = {LANGUAGE}; // ISO 639-1 (2-char) language code (en, de, ...) + int8_t volume = SOUND_VOLUME; // Volume (0-100%) feedback (if directly changed i.e. via CoverUI or WebApp) HallConfig hall_configs[MAX_HALL_INPUTS] = { - {HallMode::emergency, HallLevel::activeLow}, // [0] OM Hall-1 input (Lift1) - {HallMode::emergency, HallLevel::activeLow}, // [1] OM Hall-2 input (Lift2) - {HallMode::stop, HallLevel::activeLow}, // [2] OM Hall-3 input (Stop1) - {HallMode::stop, HallLevel::activeLow}, // [3] OM Hall-4 input (Stop2) + {HallMode::EMERGENCY, HallLevel::ACTIVE_LOW}, // [0] OM Hall-1 input (Lift1) + {HallMode::EMERGENCY, HallLevel::ACTIVE_LOW}, // [1] OM Hall-2 input (Lift2) + {HallMode::STOP, HallLevel::ACTIVE_LOW}, // [2] OM Hall-3 input (Stop1) + {HallMode::STOP, HallLevel::ACTIVE_LOW}, // [3] OM Hall-4 input (Stop2) // [4] Stock-CoverUI-1 ... [9] Stock-CoverUI-6 defaults to off }; // INFO: Before adding a new member here: Decide if and how much hall_configs spares do we like to have diff --git a/Firmware/LowLevel/src/main.cpp b/Firmware/LowLevel/src/main.cpp index 34188f6a..39187bb6 100644 --- a/Firmware/LowLevel/src/main.cpp +++ b/Firmware/LowLevel/src/main.cpp @@ -19,7 +19,7 @@ #include #include #include "datatypes.h" -#include "config.h" +#include "config_defaults.h" #include "pins.h" #include "ui_board.h" #include "imu.h" @@ -366,9 +366,7 @@ void setup() { // Therefore, we pause the other core until setup() was a success rp2040.idleOtherCore(); -#ifdef USB_DEBUG DEBUG_BEGIN(9600); -#endif emergency_latch = true; ROS_running = false; From 4f11010a837ba9c8fcad3a1768f548b6cd712c0b Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?J=C3=B6rg=20Ebeling?= Date: Sat, 12 Oct 2024 20:38:42 +0200 Subject: [PATCH 11/32] Minor LittleFS implementation changes --- Firmware/LowLevel/include/config_defaults.h | 2 ++ Firmware/LowLevel/src/main.cpp | 16 +++++++++------- 2 files changed, 11 insertions(+), 7 deletions(-) diff --git a/Firmware/LowLevel/include/config_defaults.h b/Firmware/LowLevel/include/config_defaults.h index 915bde0a..9e6044fb 100644 --- a/Firmware/LowLevel/include/config_defaults.h +++ b/Firmware/LowLevel/include/config_defaults.h @@ -23,4 +23,6 @@ #define SOUND_VOLUME 80 // Volume (0-100%) #define LANGUAGE 'e', 'n' // ISO 639-1 (2-char) language code (en, de, ...) +#define CONFIG_FILENAME "/openmower.cfg" // Where our llhl_config get saved in LittleFS (flash) + #endif // _CONFIG_H \ No newline at end of file diff --git a/Firmware/LowLevel/src/main.cpp b/Firmware/LowLevel/src/main.cpp index e5917204..6382cc99 100644 --- a/Firmware/LowLevel/src/main.cpp +++ b/Firmware/LowLevel/src/main.cpp @@ -14,17 +14,18 @@ // SOFTWARE. // // -#include #include #include +#include +#include #include -#include "datatypes.h" + #include "config_defaults.h" +#include "datatypes.h" +#include "debug.h" +#include "imu.h" #include "pins.h" #include "ui_board.h" -#include "imu.h" -#include "debug.h" -#include #ifdef ENABLE_SOUND_MODULE #include @@ -119,7 +120,6 @@ uint8_t ui_topic_bitmask = Topic_set_leds; // UI subscription, default to Set_LE uint16_t ui_interval = 1000; // UI send msg (LED/State) interval (ms) struct ll_high_level_config llhl_config; // LL/HL configuration (is initialized with YF-C500 defaults) -const String CONFIG_FILENAME = "/openmower.cfg"; uint16_t config_crc_in_flash = 0; void sendMessage(void *message, size_t size); @@ -550,7 +550,7 @@ void sendConfigMessage(uint8_t pkt_type) { size_t msg_size = sizeof(struct ll_high_level_config) + 3; // + 1 type + 2 crc uint8_t *msg = (uint8_t *)malloc(msg_size); if (msg == NULL) - return; // malloc() failed + return; *msg = pkt_type; memcpy(msg + 1, &llhl_config, sizeof(struct ll_high_level_config)); // Copy our live config into the message, behind type sendMessage(msg, msg_size); @@ -833,6 +833,8 @@ void readConfigFromFlash() { // read config uint8_t *buffer = (uint8_t *)malloc(f.size()); f.read(buffer, size); + if (buffer == NULL) + return; f.close(); // check the CRC From 0075f68f2e3895b81aa5c7ab4c170bb7a42971e8 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?J=C3=B6rg=20Ebeling?= Date: Mon, 14 Oct 2024 22:19:31 +0200 Subject: [PATCH 12/32] Intermediate result after protocol implementation with ROS --- Firmware/LowLevel/include/config_defaults.h | 28 ------------ Firmware/LowLevel/include/debug.h | 42 ------------------ Firmware/LowLevel/src/datatypes.h | 47 +++++++++++---------- 3 files changed, 25 insertions(+), 92 deletions(-) delete mode 100644 Firmware/LowLevel/include/config_defaults.h delete mode 100644 Firmware/LowLevel/include/debug.h diff --git a/Firmware/LowLevel/include/config_defaults.h b/Firmware/LowLevel/include/config_defaults.h deleted file mode 100644 index 9e6044fb..00000000 --- a/Firmware/LowLevel/include/config_defaults.h +++ /dev/null @@ -1,28 +0,0 @@ -#ifndef _CONFIG_H -#define _CONFIG_H - -#define BATT_ABS_MAX 28.7f -#define BATT_ABS_MIN 21.7f - -#define BATT_EMPTY BATT_ABS_MIN + 0.3f -#define BATT_FULL BATT_ABS_MAX - 0.3f - -#define V_BATT_CUTOFF 29.0f - -#define TILT_EMERGENCY_MILLIS 2500 // Time for a single wheel to be lifted in order to count as emergency (0 disable). This is to filter uneven ground. -#define LIFT_EMERGENCY_MILLIS 100 // Time for both wheels to be lifted in order to count as emergency (0 disable). This is to filter uneven ground. - -#define V_CHARGE_MAX 30.0f // Default YF-C500 max. charge voltage -#define I_CHARGE_MAX 1.5f // Default YF-C500 max. charge current - -#define V_CHARGE_ABS_MAX 40.0f // Absolute max. limited by D2/D3 Schottky -#define I_CHARGE_ABS_MAX 5.0f // Absolute max. limited by D2/D3 Schottky - -#define RAIN_THRESHOLD 700U // (Yet) Stock-CoverUI exclusive raw ADC value. Is the measured value is lower, it rains - -#define SOUND_VOLUME 80 // Volume (0-100%) -#define LANGUAGE 'e', 'n' // ISO 639-1 (2-char) language code (en, de, ...) - -#define CONFIG_FILENAME "/openmower.cfg" // Where our llhl_config get saved in LittleFS (flash) - -#endif // _CONFIG_H \ No newline at end of file diff --git a/Firmware/LowLevel/include/debug.h b/Firmware/LowLevel/include/debug.h deleted file mode 100644 index 407a0052..00000000 --- a/Firmware/LowLevel/include/debug.h +++ /dev/null @@ -1,42 +0,0 @@ -// Created by Apehaenger on 02/02/23. -// -// This work is licensed under a Creative Commons Attribution-NonCommercial-ShareAlike 4.0 International License. -// -// Feel free to use the design in your private/educational projects, but don't try to sell the design or products based on it without getting my consent first. -// -// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -// SOFTWARE. -// -// -#ifndef _DEBUG_H_ -#define _DEBUG_H_ - -// Define to stream debugging messages via USB -//#define USB_DEBUG -#define DEBUG_PREFIX "" // You may define a debug prefix string - -#ifdef USB_DEBUG -#define DEBUG_SERIAL Serial - -// Some bloody simple debug macros which superfluous '#ifdef USB_DEBUG' ... -#define DEBUG_BEGIN(b) \ - DEBUG_SERIAL.begin(b); \ - while (!DEBUG_SERIAL) \ - ; -#define DEBUG_PRINTF(fmt, ...) \ - do \ - { \ - DEBUG_SERIAL.printf(DEBUG_PREFIX fmt, ##__VA_ARGS__); \ - } while (0) -#else -#define DEBUG_BEGIN(b) -#define DEBUG_PRINTF(fmt, ...) -#endif - - -#endif // _DEBUG_H_ diff --git a/Firmware/LowLevel/src/datatypes.h b/Firmware/LowLevel/src/datatypes.h index a985c5c6..440b26e6 100644 --- a/Firmware/LowLevel/src/datatypes.h +++ b/Firmware/LowLevel/src/datatypes.h @@ -19,7 +19,6 @@ #define _DATATYPES_H #include -#include "config_defaults.h" #define PACKET_ID_LL_STATUS 1 #define PACKET_ID_LL_IMU 2 @@ -137,27 +136,30 @@ struct ll_ui_event { } __attribute__((packed)); #pragma pack(pop) -#define LL_HIGH_LEVEL_CONFIG_BIT_DFPIS5V 1 << 0 // Enable full sound via mower_config env var "OM_DFP_IS_5V" -#define LL_HIGH_LEVEL_CONFIG_BIT_BACKGROUND_SOUNDS 1 << 1 // Enable background sounds +#define LL_HIGH_LEVEL_CONFIG_BIT_DFPIS5V (1 << 0) // Enable full sound via mower_config env var "OM_DFP_IS_5V" +#define LL_HIGH_LEVEL_CONFIG_BIT_BACKGROUND_SOUNDS (1 << 1) // Enable background sounds + +#define LL_HIGH_LEVEL_CONFIG_BIT_HL_IS_LEADING ((LL_HIGH_LEVEL_CONFIG_BIT_DFPIS5V) | (LL_HIGH_LEVEL_CONFIG_BIT_BACKGROUND_SOUNDS)) // Config bits where HL is leading typedef char iso639_1[2]; // Two char ISO 639-1 language code -enum class HallMode : uint8_t { +enum class HallMode : unsigned int { OFF = 0, - EMERGENCY, // Triggers emergency with lift & tilt functionality + LIFT_TILT, // Wheel lifted and/or wheels tilted functionality STOP, // Stop mower - PAUSE // Pause the mower (not yet implemented in ROS) + PAUSE, // Pause the mower (not yet implemented in ROS) + UNDEFINED // This is used by foreign side to inform that it doesn't has a configuration for this sensor }; // FIXME: Decide later which is more comfortable, activeLow = 0 | 1 -enum class HallLevel : uint8_t { +enum class HallLevel : unsigned int { ACTIVE_LOW = 0, // If Hall-Sensor (or button) is active/triggered we've this level on our GPIO ACTIVE_HIGH }; #pragma pack(push, 1) struct HallConfig { - HallMode mode : 4; + HallMode mode : 3; HallLevel level : 1; } __attribute__((packed)); #pragma pack(pop) @@ -172,23 +174,24 @@ struct ll_high_level_config { // uint8_t type; Just for illustration. Get set in wire buffer with type PACKET_ID_LL_HIGH_LEVEL_CONFIG_REQ or PACKET_ID_LL_HIGH_LEVEL_CONFIG_RSP - uint8_t config_bitmask = 0; // See LL_HIGH_LEVEL_CONFIG_BIT_* - uint16_t rain_threshold = RAIN_THRESHOLD; // If (stock CoverUI) rain value < rain_threshold then it rains. Expected to differ between C500, SA and SC types - float v_charge_cutoff = V_CHARGE_MAX; // Protective max. charging voltage before charging get switched off - float i_charge_cutoff = I_CHARGE_MAX; // Protective max. charging current before charging get switched off - float v_battery_cutoff = V_BATT_CUTOFF; // Protective max. battery voltage before charging get switched off - float v_battery_empty = BATT_EMPTY; // Empty battery voltage used for % calc of capacity - float v_battery_full = BATT_FULL; // Full battery voltage used for % calc of capacity - uint16_t lift_period = LIFT_EMERGENCY_MILLIS; // Period (ms) for both wheels to be lifted in order to count as emergency (0 disable, 0xFFFF do not change). This is to filter uneven ground - uint16_t tilt_period = TILT_EMERGENCY_MILLIS; // Period (ms) for a single wheel to be lifted in order to count as emergency (0 disable, 0xFFFF do not change). This is to filter uneven ground - iso639_1 language = {LANGUAGE}; // ISO 639-1 (2-char) language code (en, de, ...) - int8_t volume = SOUND_VOLUME; // Volume (0-100%) feedback (if directly changed i.e. via CoverUI or WebApp) + uint8_t config_bitmask = 0; // See LL_HIGH_LEVEL_CONFIG_BIT_* + uint16_t rain_threshold = 700; // If (stock CoverUI) rain value < rain_threshold then it rains. Expected to differ between C500, SA and SC types (0xFFFF = unknown) + float v_charge_cutoff = 30.0f; // Protective max. charging voltage before charging get switched off (NAN = unknown) + float i_charge_cutoff = 1.5f; // Protective max. charging current before charging get switched off (NAN = unknown) + float v_battery_cutoff = 29.0f; // Protective max. battery voltage before charging get switched off (NAN = unknown) + float v_battery_empty = 21.7f + 0.3f; // Empty battery voltage used for % calc of capacity (NAN = unknown) + float v_battery_full = 28.7f - 0.3f; // Full battery voltage used for % calc of capacity (NAN = unknown) + uint16_t lift_period = 100; // Period (ms) for both wheels to be lifted in order to count as emergency (0 = disable, 0xFFFF = unknown). This is to filter uneven ground + uint16_t tilt_period = 2500; // Period (ms) for a single wheel to be lifted in order to count as emergency (0 = disable, 0xFFFF = unknown). This is to filter uneven ground + float shutdown_esc_max_pitch = 15.0f; // Do not shutdown ESCs if absolute pitch angle is greater than this (to be implemented) + iso639_1 language = {'e', 'n'}; // ISO 639-1 (2-char) language code (en, de, ...) + uint8_t volume = 80; // Volume (0-100%) feedback (if directly changed i.e. via CoverUI or WebApp) (0xff = do not change) HallConfig hall_configs[MAX_HALL_INPUTS] = { - {HallMode::EMERGENCY, HallLevel::ACTIVE_LOW}, // [0] OM Hall-1 input (Lift1) - {HallMode::EMERGENCY, HallLevel::ACTIVE_LOW}, // [1] OM Hall-2 input (Lift2) + {HallMode::LIFT_TILT, HallLevel::ACTIVE_LOW}, // [0] OM Hall-1 input (Lift1) + {HallMode::LIFT_TILT, HallLevel::ACTIVE_LOW}, // [1] OM Hall-2 input (Lift2) {HallMode::STOP, HallLevel::ACTIVE_LOW}, // [2] OM Hall-3 input (Stop1) {HallMode::STOP, HallLevel::ACTIVE_LOW}, // [3] OM Hall-4 input (Stop2) - // [4] Stock-CoverUI-1 ... [9] Stock-CoverUI-6 defaults to off + // [4] Stock-CoverUI-1 ... [9] Stock-CoverUI-6 default to off }; // INFO: Before adding a new member here: Decide if and how much hall_configs spares do we like to have From 37f2ac6d2f30e52d7e6433d08c7101fa9e7e4b48 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?J=C3=B6rg=20Ebeling?= Date: Mon, 14 Oct 2024 23:37:21 +0200 Subject: [PATCH 13/32] Missing commit --- Firmware/LowLevel/src/main.cpp | 64 ++++++++++++++++++++++------------ 1 file changed, 42 insertions(+), 22 deletions(-) diff --git a/Firmware/LowLevel/src/main.cpp b/Firmware/LowLevel/src/main.cpp index 6382cc99..4c43eb84 100644 --- a/Firmware/LowLevel/src/main.cpp +++ b/Firmware/LowLevel/src/main.cpp @@ -20,9 +20,7 @@ #include #include -#include "config_defaults.h" #include "datatypes.h" -#include "debug.h" #include "imu.h" #include "pins.h" #include "ui_board.h" @@ -119,8 +117,10 @@ uint16_t ui_version = 0; // Last received UI firmware version uint8_t ui_topic_bitmask = Topic_set_leds; // UI subscription, default to Set_LEDs uint16_t ui_interval = 1000; // UI send msg (LED/State) interval (ms) -struct ll_high_level_config llhl_config; // LL/HL configuration (is initialized with YF-C500 defaults) +// LL/HL config +#define CONFIG_FILENAME "/openmower.cfg" // Where our llhl_config get saved in LittleFS (flash) uint16_t config_crc_in_flash = 0; +struct ll_high_level_config llhl_config; // LL/HL configuration (is initialized with YF-C500 defaults) void sendMessage(void *message, size_t size); void sendUIMessage(void *message, size_t size); @@ -194,8 +194,8 @@ void updateEmergency() { tilt_emergency_started = 0; } - if ((LIFT_EMERGENCY_MILLIS > 0 && lift_emergency_started > 0 && (millis() - lift_emergency_started) >= LIFT_EMERGENCY_MILLIS) || - (TILT_EMERGENCY_MILLIS > 0 && tilt_emergency_started > 0 && (millis() - tilt_emergency_started) >= TILT_EMERGENCY_MILLIS)) { + if ((llhl_config.lift_period > 0 && lift_emergency_started > 0 && (millis() - lift_emergency_started) >= llhl_config.lift_period) || + (llhl_config.tilt_period > 0 && tilt_emergency_started > 0 && (millis() - tilt_emergency_started) >= llhl_config.tilt_period)) { emergency_state |= (emergency_read & LL_EMERGENCY_BITS_LIFT); } @@ -229,7 +229,7 @@ void manageUILEDS() { setLed(leds_message, LED_CHARGING, LED_off); // Show Info Battery state - if (status_message.v_battery >= (BATT_EMPTY + 2.0f)) + if (status_message.v_battery >= (llhl_config.v_battery_empty + 2.0f)) setLed(leds_message, LED_BATTERY_LOW, LED_off); else setLed(leds_message, LED_BATTERY_LOW, LED_on); @@ -369,7 +369,9 @@ void setup() { // Therefore, we pause the other core until setup() was a success rp2040.idleOtherCore(); - DEBUG_BEGIN(9600); +#ifdef USB_DEBUG + DEBUG_SERIAL.begin(9600); +#endif emergency_latch = true; ROS_running = false; @@ -546,7 +548,7 @@ void onUIPacketReceived(const uint8_t *buffer, size_t size) { } } -void sendConfigMessage(uint8_t pkt_type) { +void sendConfigMessage(const uint8_t pkt_type) { size_t msg_size = sizeof(struct ll_high_level_config) + 3; // + 1 type + 2 crc uint8_t *msg = (uint8_t *)malloc(msg_size); if (msg == NULL) @@ -557,27 +559,45 @@ void sendConfigMessage(uint8_t pkt_type) { free(msg); } -void applyConfig(const uint8_t *buffer, size_t size) { - // This is a flexible length package where the size may vary when ll_high_level_config struct got enhanced only on one side. +void applyConfig(const uint8_t *buffer, const size_t size) { + // This is a flexible length packet where the size may vary when ll_high_level_config struct got enhanced only on one side. // If payload size is larger than our struct size, ensure that we only copy those we know of = our struct size. // If payload size is smaller than our struct size, copy only the payload we got, but ensure that the unsent member(s) have reasonable defaults. size_t payload_size = min(sizeof(ll_high_level_config), size - 2); // exclude crc // Use a temporary config for easier sanity adaption and copy our live config, which has at least reasonable defaults. // The live config copy ensures that we've reasonable values for the case that HL config struct is older (smaller) than ours. - auto tmp_config = llhl_config; + auto hl_config = llhl_config; // Copy payload to temporary config - memcpy(&tmp_config, buffer, payload_size); + memcpy(&hl_config, buffer, payload_size); + + // Takeover of HL leading config values + llhl_config.config_bitmask = (llhl_config.config_bitmask & ~LL_HIGH_LEVEL_CONFIG_BIT_HL_IS_LEADING) | (hl_config.config_bitmask & LL_HIGH_LEVEL_CONFIG_BIT_HL_IS_LEADING); - // Sanity - tmp_config.v_charge_cutoff = min(tmp_config.v_charge_cutoff, V_CHARGE_ABS_MAX); // Fix exceed of hardware limits - tmp_config.i_charge_cutoff = min(tmp_config.i_charge_cutoff, I_CHARGE_ABS_MAX); // Fix exceed of hardware limits + // Set HL leading member if they're not "undefined" + // TODO: Not that nice :-/ Is there no more clever way? Even with a templated function, I do see similar 8 lines here - // Make config live - llhl_config = tmp_config; + if (hl_config.rain_threshold != 0xffff) llhl_config.rain_threshold = hl_config.rain_threshold; + if (!std::isnan(hl_config.v_charge_cutoff)) llhl_config.v_charge_cutoff = min(hl_config.v_charge_cutoff, 40.0f); // Absolute max. limited by D2/D3 Schottky + if (!std::isnan(hl_config.i_charge_cutoff)) llhl_config.i_charge_cutoff = min(hl_config.i_charge_cutoff, 5.0f); // Absolute max. limited by D2/D3 Schottky + if (!std::isnan(hl_config.v_battery_cutoff)) llhl_config.v_battery_cutoff = hl_config.v_battery_cutoff; + if (!std::isnan(hl_config.v_battery_empty)) llhl_config.v_battery_empty = hl_config.v_battery_empty; + if (!std::isnan(hl_config.v_battery_full)) llhl_config.v_battery_full = hl_config.v_battery_full; + if (hl_config.lift_period != 0xffff) hl_config.lift_period = hl_config.lift_period; + if (hl_config.tilt_period != 0xffff) hl_config.tilt_period = hl_config.tilt_period; - // PR-80: Assign volume & language if not already stored in flash-config + // HL is always leading for language + strncpy(llhl_config.language, hl_config.language, 2); + + // HL send 0xff if it doesn't provide a volume + if (hl_config.volume != 0xff) llhl_config.volume = llhl_config.volume; + + // Take over those hall inputs which are not undefined + for (size_t i = 0; i < MAX_HALL_INPUTS; i++) { + if (hl_config.hall_configs[i].mode != HallMode::UNDEFINED) + llhl_config.hall_configs[i] = hl_config.hall_configs[i]; + } } void onPacketReceived(const uint8_t *buffer, size_t size) { @@ -715,8 +735,8 @@ void loop() { status_message.status_bitmask = (status_message.status_bitmask & 0b11011111) | ((sound_available & 0b1) << 5); // calculate percent value accu filling - float delta = BATT_FULL - BATT_EMPTY; - float vo = status_message.v_battery - BATT_EMPTY; + float delta = llhl_config.v_battery_full - llhl_config.v_battery_empty; + float vo = status_message.v_battery - llhl_config.v_battery_empty; status_message.batt_percentage = vo / delta * 100; if (status_message.batt_percentage > 100) status_message.batt_percentage = 100; @@ -791,7 +811,7 @@ void sendMessage(void *message, size_t size) { data_pointer[size - 1] = (crc >> 8) & 0xFF; data_pointer[size - 2] = crc & 0xFF; - packetSerial.send((uint8_t *) message, size); + packetSerial.send(data_pointer, size); } void sendUIMessage(void *message, size_t size) { @@ -832,9 +852,9 @@ void readConfigFromFlash() { // read config uint8_t *buffer = (uint8_t *)malloc(f.size()); - f.read(buffer, size); if (buffer == NULL) return; + f.read(buffer, size); f.close(); // check the CRC From 9e24b05d8f51006399ea44ff7aff8b5798a692c1 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?J=C3=B6rg=20Ebeling?= Date: Fri, 18 Oct 2024 22:54:19 +0200 Subject: [PATCH 14/32] Intermediate commit #2 --- Firmware/LowLevel/src/datatypes.h | 21 +++++++++--------- Firmware/LowLevel/src/main.cpp | 36 +++++++++++++------------------ 2 files changed, 26 insertions(+), 31 deletions(-) diff --git a/Firmware/LowLevel/src/datatypes.h b/Firmware/LowLevel/src/datatypes.h index 440b26e6..0222c954 100644 --- a/Firmware/LowLevel/src/datatypes.h +++ b/Firmware/LowLevel/src/datatypes.h @@ -136,10 +136,11 @@ struct ll_ui_event { } __attribute__((packed)); #pragma pack(pop) -#define LL_HIGH_LEVEL_CONFIG_BIT_DFPIS5V (1 << 0) // Enable full sound via mower_config env var "OM_DFP_IS_5V" -#define LL_HIGH_LEVEL_CONFIG_BIT_BACKGROUND_SOUNDS (1 << 1) // Enable background sounds +#define LL_HIGH_LEVEL_CONFIG_BIT_DFPIS5V (1 << 0) // Enable full sound via mower_config env var "OM_DFP_IS_5V" +#define LL_HIGH_LEVEL_CONFIG_BIT_BACKGROUND_SOUNDS (1 << 1) // Enable background sounds +#define LL_HIGH_LEVEL_CONFIG_BIT_IGNORE_CHARGING_CURRENT (1 << 2) // Ignore charging current -#define LL_HIGH_LEVEL_CONFIG_BIT_HL_IS_LEADING ((LL_HIGH_LEVEL_CONFIG_BIT_DFPIS5V) | (LL_HIGH_LEVEL_CONFIG_BIT_BACKGROUND_SOUNDS)) // Config bits where HL is leading +#define LL_HIGH_LEVEL_CONFIG_BIT_HL_IS_LEADING (LL_HIGH_LEVEL_CONFIG_BIT_DFPIS5V | LL_HIGH_LEVEL_CONFIG_BIT_BACKGROUND_SOUNDS | LL_HIGH_LEVEL_CONFIG_BIT_IGNORE_CHARGING_CURRENT) typedef char iso639_1[2]; // Two char ISO 639-1 language code @@ -176,15 +177,15 @@ struct ll_high_level_config { uint8_t config_bitmask = 0; // See LL_HIGH_LEVEL_CONFIG_BIT_* uint16_t rain_threshold = 700; // If (stock CoverUI) rain value < rain_threshold then it rains. Expected to differ between C500, SA and SC types (0xFFFF = unknown) - float v_charge_cutoff = 30.0f; // Protective max. charging voltage before charging get switched off (NAN = unknown) - float i_charge_cutoff = 1.5f; // Protective max. charging current before charging get switched off (NAN = unknown) - float v_battery_cutoff = 29.0f; // Protective max. battery voltage before charging get switched off (NAN = unknown) - float v_battery_empty = 21.7f + 0.3f; // Empty battery voltage used for % calc of capacity (NAN = unknown) - float v_battery_full = 28.7f - 0.3f; // Full battery voltage used for % calc of capacity (NAN = unknown) + float v_charge_cutoff = 30.0f; // Protective max. charging voltage before charging get switched off (-1 = unknown) + float i_charge_cutoff = 1.5f; // Protective max. charging current before charging get switched off (-1 = unknown) + float v_battery_cutoff = 29.0f; // Protective max. battery voltage before charging get switched off (-1 = unknown) + float v_battery_empty = 21.7f + 0.3f; // Empty battery voltage used for % calc of capacity (-1 = unknown) + float v_battery_full = 28.7f - 0.3f; // Full battery voltage used for % calc of capacity (-1 = unknown) uint16_t lift_period = 100; // Period (ms) for both wheels to be lifted in order to count as emergency (0 = disable, 0xFFFF = unknown). This is to filter uneven ground uint16_t tilt_period = 2500; // Period (ms) for a single wheel to be lifted in order to count as emergency (0 = disable, 0xFFFF = unknown). This is to filter uneven ground - float shutdown_esc_max_pitch = 15.0f; // Do not shutdown ESCs if absolute pitch angle is greater than this (to be implemented) - iso639_1 language = {'e', 'n'}; // ISO 639-1 (2-char) language code (en, de, ...) + float shutdown_esc_max_pitch = 0.0f; // Do not shutdown ESCs if absolute pitch angle is greater than this (0 = disable, 0xffff = unknown) (to be implemented) + iso639_1 language = {'e', 'n'}; // ISO 639-1 (2-char) language code (en, de, ...) uint8_t volume = 80; // Volume (0-100%) feedback (if directly changed i.e. via CoverUI or WebApp) (0xff = do not change) HallConfig hall_configs[MAX_HALL_INPUTS] = { {HallMode::LIFT_TILT, HallLevel::ACTIVE_LOW}, // [0] OM Hall-1 input (Lift1) diff --git a/Firmware/LowLevel/src/main.cpp b/Firmware/LowLevel/src/main.cpp index 4c43eb84..8295bd1b 100644 --- a/Firmware/LowLevel/src/main.cpp +++ b/Firmware/LowLevel/src/main.cpp @@ -572,32 +572,29 @@ void applyConfig(const uint8_t *buffer, const size_t size) { // Copy payload to temporary config memcpy(&hl_config, buffer, payload_size); - // Takeover of HL leading config values + // Takeover HL leading config_bitmask values. This is only to illustrate that we may mix HL as well as LL leading bits here (if required some when). + // FIXME: Check if bitfields would look better llhl_config.config_bitmask = (llhl_config.config_bitmask & ~LL_HIGH_LEVEL_CONFIG_BIT_HL_IS_LEADING) | (hl_config.config_bitmask & LL_HIGH_LEVEL_CONFIG_BIT_HL_IS_LEADING); - // Set HL leading member if they're not "undefined" - // TODO: Not that nice :-/ Is there no more clever way? Even with a templated function, I do see similar 8 lines here - + // Take over HL members if they're not "undefined" if (hl_config.rain_threshold != 0xffff) llhl_config.rain_threshold = hl_config.rain_threshold; - if (!std::isnan(hl_config.v_charge_cutoff)) llhl_config.v_charge_cutoff = min(hl_config.v_charge_cutoff, 40.0f); // Absolute max. limited by D2/D3 Schottky - if (!std::isnan(hl_config.i_charge_cutoff)) llhl_config.i_charge_cutoff = min(hl_config.i_charge_cutoff, 5.0f); // Absolute max. limited by D2/D3 Schottky - if (!std::isnan(hl_config.v_battery_cutoff)) llhl_config.v_battery_cutoff = hl_config.v_battery_cutoff; - if (!std::isnan(hl_config.v_battery_empty)) llhl_config.v_battery_empty = hl_config.v_battery_empty; - if (!std::isnan(hl_config.v_battery_full)) llhl_config.v_battery_full = hl_config.v_battery_full; - if (hl_config.lift_period != 0xffff) hl_config.lift_period = hl_config.lift_period; - if (hl_config.tilt_period != 0xffff) hl_config.tilt_period = hl_config.tilt_period; - - // HL is always leading for language - strncpy(llhl_config.language, hl_config.language, 2); + if (hl_config.v_charge_cutoff >= 0) llhl_config.v_charge_cutoff = min(hl_config.v_charge_cutoff, 40.0f); // Absolute max. limited by D2/D3 Schottky + if (hl_config.i_charge_cutoff >= 0) llhl_config.i_charge_cutoff = min(hl_config.i_charge_cutoff, 5.0f); // Absolute max. limited by D2/D3 Schottky + if (hl_config.v_battery_cutoff >= 0) llhl_config.v_battery_cutoff = hl_config.v_battery_cutoff; + if (hl_config.v_battery_empty >= 0) llhl_config.v_battery_empty = hl_config.v_battery_empty; + if (hl_config.v_battery_full >= 0) llhl_config.v_battery_full = hl_config.v_battery_full; + if (hl_config.lift_period != 0xffff) llhl_config.lift_period = hl_config.lift_period; + if (hl_config.tilt_period != 0xffff) llhl_config.tilt_period = hl_config.tilt_period; + if (hl_config.volume != 0xff) llhl_config.volume = hl_config.volume; - // HL send 0xff if it doesn't provide a volume - if (hl_config.volume != 0xff) llhl_config.volume = llhl_config.volume; + strncpy(llhl_config.language, hl_config.language, 2); // HL always force the language // Take over those hall inputs which are not undefined for (size_t i = 0; i < MAX_HALL_INPUTS; i++) { if (hl_config.hall_configs[i].mode != HallMode::UNDEFINED) llhl_config.hall_configs[i] = hl_config.hall_configs[i]; } + // FIXME: TODO: Hall/emergency implementation } void onPacketReceived(const uint8_t *buffer, size_t size) { @@ -627,21 +624,18 @@ void onPacketReceived(const uint8_t *buffer, size_t size) { if (!ROS_running) { // ROS is running (again (i.e. due to restart after reconfiguration)) ROS_running = true; - - // Send current LL config (and request HL config response) - sendConfigMessage(PACKET_ID_LL_HIGH_LEVEL_CONFIG_REQ); } } else if (buffer[0] == PACKET_ID_LL_HIGH_LEVEL_STATE && size == sizeof(struct ll_high_level_state)) { // copy the state last_high_level_state = *((struct ll_high_level_state *) buffer); } else if (buffer[0] == PACKET_ID_LL_HIGH_LEVEL_CONFIG_REQ || buffer[0] == PACKET_ID_LL_HIGH_LEVEL_CONFIG_RSP) { - applyConfig(buffer + 1, size - 1); // Skip type + applyConfig(buffer + 1, size - 1); // Skip type // Store in flash saveConfigToFlash(); if (buffer[0] == PACKET_ID_LL_HIGH_LEVEL_CONFIG_REQ) - sendConfigMessage(PACKET_ID_LL_HIGH_LEVEL_CONFIG_RSP); + sendConfigMessage(PACKET_ID_LL_HIGH_LEVEL_CONFIG_RSP); // Other side requested a config response } } From 7eaa6fdaa85ef2beff9e76e51498340bde1732b6 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?J=C3=B6rg=20Ebeling?= Date: Sat, 19 Oct 2024 00:07:59 +0200 Subject: [PATCH 15/32] Adjust v_charge_cutoff to MAX20405 --- Firmware/LowLevel/src/main.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Firmware/LowLevel/src/main.cpp b/Firmware/LowLevel/src/main.cpp index 8295bd1b..eb9aabee 100644 --- a/Firmware/LowLevel/src/main.cpp +++ b/Firmware/LowLevel/src/main.cpp @@ -578,7 +578,7 @@ void applyConfig(const uint8_t *buffer, const size_t size) { // Take over HL members if they're not "undefined" if (hl_config.rain_threshold != 0xffff) llhl_config.rain_threshold = hl_config.rain_threshold; - if (hl_config.v_charge_cutoff >= 0) llhl_config.v_charge_cutoff = min(hl_config.v_charge_cutoff, 40.0f); // Absolute max. limited by D2/D3 Schottky + if (hl_config.v_charge_cutoff >= 0) llhl_config.v_charge_cutoff = min(hl_config.v_charge_cutoff, 36.0f); // Rated max. limited by MAX20405 if (hl_config.i_charge_cutoff >= 0) llhl_config.i_charge_cutoff = min(hl_config.i_charge_cutoff, 5.0f); // Absolute max. limited by D2/D3 Schottky if (hl_config.v_battery_cutoff >= 0) llhl_config.v_battery_cutoff = hl_config.v_battery_cutoff; if (hl_config.v_battery_empty >= 0) llhl_config.v_battery_empty = hl_config.v_battery_empty; From 5f5d5b8797411087f2839264d0eae054d18cc706 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?J=C3=B6rg=20Ebeling?= Date: Sun, 20 Oct 2024 20:36:13 +0200 Subject: [PATCH 16/32] Change config_bitmask to option bitfield --- Firmware/LowLevel/src/datatypes.h | 15 ++++++++------- Firmware/LowLevel/src/main.cpp | 20 +++++++++----------- 2 files changed, 17 insertions(+), 18 deletions(-) diff --git a/Firmware/LowLevel/src/datatypes.h b/Firmware/LowLevel/src/datatypes.h index 0222c954..98c43503 100644 --- a/Firmware/LowLevel/src/datatypes.h +++ b/Firmware/LowLevel/src/datatypes.h @@ -136,11 +136,13 @@ struct ll_ui_event { } __attribute__((packed)); #pragma pack(pop) -#define LL_HIGH_LEVEL_CONFIG_BIT_DFPIS5V (1 << 0) // Enable full sound via mower_config env var "OM_DFP_IS_5V" -#define LL_HIGH_LEVEL_CONFIG_BIT_BACKGROUND_SOUNDS (1 << 1) // Enable background sounds -#define LL_HIGH_LEVEL_CONFIG_BIT_IGNORE_CHARGING_CURRENT (1 << 2) // Ignore charging current - -#define LL_HIGH_LEVEL_CONFIG_BIT_HL_IS_LEADING (LL_HIGH_LEVEL_CONFIG_BIT_DFPIS5V | LL_HIGH_LEVEL_CONFIG_BIT_BACKGROUND_SOUNDS | LL_HIGH_LEVEL_CONFIG_BIT_IGNORE_CHARGING_CURRENT) +#pragma pack(push, 1) +struct ConfigOptions { + bool dfp_is_5v : 1; + bool background_sounds : 1; + bool ignore_charging_current : 1; +} __attribute__((packed)); +#pragma pack(pop) typedef char iso639_1[2]; // Two char ISO 639-1 language code @@ -152,7 +154,6 @@ enum class HallMode : unsigned int { UNDEFINED // This is used by foreign side to inform that it doesn't has a configuration for this sensor }; -// FIXME: Decide later which is more comfortable, activeLow = 0 | 1 enum class HallLevel : unsigned int { ACTIVE_LOW = 0, // If Hall-Sensor (or button) is active/triggered we've this level on our GPIO ACTIVE_HIGH @@ -175,7 +176,7 @@ struct ll_high_level_config { // uint8_t type; Just for illustration. Get set in wire buffer with type PACKET_ID_LL_HIGH_LEVEL_CONFIG_REQ or PACKET_ID_LL_HIGH_LEVEL_CONFIG_RSP - uint8_t config_bitmask = 0; // See LL_HIGH_LEVEL_CONFIG_BIT_* + ConfigOptions options = {0, 0, 0}; uint16_t rain_threshold = 700; // If (stock CoverUI) rain value < rain_threshold then it rains. Expected to differ between C500, SA and SC types (0xFFFF = unknown) float v_charge_cutoff = 30.0f; // Protective max. charging voltage before charging get switched off (-1 = unknown) float i_charge_cutoff = 1.5f; // Protective max. charging current before charging get switched off (-1 = unknown) diff --git a/Firmware/LowLevel/src/main.cpp b/Firmware/LowLevel/src/main.cpp index eb9aabee..304c98ec 100644 --- a/Firmware/LowLevel/src/main.cpp +++ b/Firmware/LowLevel/src/main.cpp @@ -117,10 +117,11 @@ uint16_t ui_version = 0; // Last received UI firmware version uint8_t ui_topic_bitmask = Topic_set_leds; // UI subscription, default to Set_LEDs uint16_t ui_interval = 1000; // UI send msg (LED/State) interval (ms) -// LL/HL config +// LL/HL config #define CONFIG_FILENAME "/openmower.cfg" // Where our llhl_config get saved in LittleFS (flash) uint16_t config_crc_in_flash = 0; struct ll_high_level_config llhl_config; // LL/HL configuration (is initialized with YF-C500 defaults) +static_assert(sizeof(ConfigOptions) == 1, "Enlarging struct ConfigOption to a sizeof > 1 will break packet compatibilty"); void sendMessage(void *message, size_t size); void sendUIMessage(void *message, size_t size); @@ -137,6 +138,7 @@ void setRaspiPower(bool power) { } void updateEmergency() { + // FIXME: Implement new hall_configs if (millis() - last_heartbeat_millis > HEARTBEAT_MILLIS) { emergency_latch = true; @@ -474,7 +476,7 @@ void setup() { sound_available = my_sound.begin(); if (sound_available) { p.neoPixelSetValue(0, 0, 0, 255, true); - my_sound.setvolume(100); + my_sound.setvolume(llhl_config.volume); my_sound.playSoundAdHoc(1); p.neoPixelSetValue(0, 255, 255, 0, true); } else { @@ -572,11 +574,11 @@ void applyConfig(const uint8_t *buffer, const size_t size) { // Copy payload to temporary config memcpy(&hl_config, buffer, payload_size); - // Takeover HL leading config_bitmask values. This is only to illustrate that we may mix HL as well as LL leading bits here (if required some when). - // FIXME: Check if bitfields would look better - llhl_config.config_bitmask = (llhl_config.config_bitmask & ~LL_HIGH_LEVEL_CONFIG_BIT_HL_IS_LEADING) | (hl_config.config_bitmask & LL_HIGH_LEVEL_CONFIG_BIT_HL_IS_LEADING); + // HL always force these + llhl_config.options = hl_config.options; + strncpy(llhl_config.language, hl_config.language, 2); - // Take over HL members if they're not "undefined" + // Take over only those HL members who are not "undefined/unknown" if (hl_config.rain_threshold != 0xffff) llhl_config.rain_threshold = hl_config.rain_threshold; if (hl_config.v_charge_cutoff >= 0) llhl_config.v_charge_cutoff = min(hl_config.v_charge_cutoff, 36.0f); // Rated max. limited by MAX20405 if (hl_config.i_charge_cutoff >= 0) llhl_config.i_charge_cutoff = min(hl_config.i_charge_cutoff, 5.0f); // Absolute max. limited by D2/D3 Schottky @@ -587,14 +589,10 @@ void applyConfig(const uint8_t *buffer, const size_t size) { if (hl_config.tilt_period != 0xffff) llhl_config.tilt_period = hl_config.tilt_period; if (hl_config.volume != 0xff) llhl_config.volume = hl_config.volume; - strncpy(llhl_config.language, hl_config.language, 2); // HL always force the language - // Take over those hall inputs which are not undefined - for (size_t i = 0; i < MAX_HALL_INPUTS; i++) { + for (size_t i = 0; i < MAX_HALL_INPUTS; i++) if (hl_config.hall_configs[i].mode != HallMode::UNDEFINED) llhl_config.hall_configs[i] = hl_config.hall_configs[i]; - } - // FIXME: TODO: Hall/emergency implementation } void onPacketReceived(const uint8_t *buffer, size_t size) { From a1a64923e8b5332a9f79310dcb0c1194d4e5e0bc Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?J=C3=B6rg=20Ebeling?= Date: Sun, 20 Oct 2024 20:52:07 +0200 Subject: [PATCH 17/32] Make IGNORE_CHARGING_CURRENT configurable via LL/HL config `options.ignore_charging_current` --- Firmware/LowLevel/platformio.ini | 41 -------------------------------- Firmware/LowLevel/src/main.cpp | 8 ++----- 2 files changed, 2 insertions(+), 47 deletions(-) diff --git a/Firmware/LowLevel/platformio.ini b/Firmware/LowLevel/platformio.ini index 4ae1fba1..da73d020 100644 --- a/Firmware/LowLevel/platformio.ini +++ b/Firmware/LowLevel/platformio.ini @@ -51,14 +51,6 @@ lib_deps = ${env.lib_deps} build_src_filter = ${env.build_src_filter} + build_flags = ${env.build_flags} -DHW_0_13_X -[env:0_13_X_IGNORE_CHARGING_CURRENT] -lib_ignore = JY901_SERIAL,JY901_I2C -lib_deps = ${env.lib_deps} - stm32duino/STM32duino LSM6DSO@^2.0.3 - powerbroker2/DFPlayerMini_Fast@^1.2.4 -build_src_filter = ${env.build_src_filter} + -build_flags = ${env.build_flags} -DHW_0_13_X -DIGNORE_CHARGING_CURRENT - [env:0_12_X] lib_ignore = JY901_SERIAL,JY901_I2C lib_deps = ${env.lib_deps} @@ -68,15 +60,6 @@ lib_deps = ${env.lib_deps} build_src_filter = ${env.build_src_filter} + + build_flags = ${env.build_flags} -DHW_0_12_X -DENABLE_SOUND_MODULE -[env:0_12_X_IGNORE_CHARGING_CURRENT] -lib_ignore = JY901_SERIAL,JY901_I2C -lib_deps = ${env.lib_deps} - stm32duino/STM32duino LSM6DSO@^2.0.3 - jpiat/PioSPI@^0.0.1 - powerbroker2/DFPlayerMini_Fast@^1.2.4 -build_src_filter = ${env.build_src_filter} + + -build_flags = ${env.build_flags} -DHW_0_12_X -DENABLE_SOUND_MODULE -DIGNORE_CHARGING_CURRENT - [env:0_11_X_MPU9250] lib_ignore = JY901_SERIAL,JY901_I2C @@ -94,14 +77,6 @@ lib_deps = ${env.lib_deps} JY901_I2C build_flags = ${env.build_flags} -DWT901_I2C -DHW_0_11_X -DENABLE_SOUND_MODULE -[env:0_11_X_WT901_IGNORE_CHARGING_CURRENT] -build_src_filter = ${env.build_src_filter} + + -lib_ignore = JY901_SERIAL -lib_deps = ${env.lib_deps} - powerbroker2/DFPlayerMini_Fast@^1.2.4 - JY901_I2C -build_flags = ${env.build_flags} -DWT901_I2C -DHW_0_11_X -DENABLE_SOUND_MODULE -DIGNORE_CHARGING_CURRENT - [env:0_10_X_MPU9250] lib_ignore = JY901_SERIAL,JY901_I2C @@ -119,13 +94,6 @@ lib_deps = ${env.lib_deps} JY901_I2C build_flags = ${env.build_flags} -DWT901_I2C -DHW_0_10_X -DENABLE_SOUND_MODULE -[env:0_10_X_WT901_IGNORE_CHARGING_CURRENT] -build_src_filter = ${env.build_src_filter} + + -lib_ignore = JY901_SERIAL -lib_deps = ${env.lib_deps} - powerbroker2/DFPlayerMini_Fast@^1.2.4 - JY901_I2C -build_flags = ${env.build_flags} -DWT901_I2C -DHW_0_10_X -DENABLE_SOUND_MODULE -DIGNORE_CHARGING_CURRENT [env:0_9_X_MPU9250] lib_ignore = JY901_SERIAL,JY901_I2C @@ -142,15 +110,6 @@ lib_deps = ${env.lib_deps} JY901_SERIAL build_flags = ${env.build_flags} -DWT901_INSTEAD_OF_SOUND -DHW_0_9_X - -[env:0_9_X_WT901_IGNORE_CHARGING_CURRENT] -lib_ignore = JY901_I2C -build_src_filter = ${env.build_src_filter} + + -lib_deps = ${env.lib_deps} - JY901_SERIAL - powerbroker2/DFPlayerMini_Fast@^1.2.4 -build_flags = ${env.build_flags} -DWT901 -DHW_0_9_X -DENABLE_SOUND_MODULE -DIGNORE_CHARGING_CURRENT - [env:0_9_X_WT901] lib_ignore = JY901_I2C build_src_filter = ${env.build_src_filter} + + diff --git a/Firmware/LowLevel/src/main.cpp b/Firmware/LowLevel/src/main.cpp index 304c98ec..6d1e71d6 100644 --- a/Firmware/LowLevel/src/main.cpp +++ b/Firmware/LowLevel/src/main.cpp @@ -717,12 +717,8 @@ void loop() { (float) analogRead(PIN_ANALOG_BATTERY_VOLTAGE) * (3.3f / 4096.0f) * ((VIN_R1 + VIN_R2) / VIN_R2); status_message.v_charge = (float) analogRead(PIN_ANALOG_CHARGE_VOLTAGE) * (3.3f / 4096.0f) * ((VIN_R1 + VIN_R2) / VIN_R2); -#ifndef IGNORE_CHARGING_CURRENT - status_message.charging_current = - (float) analogRead(PIN_ANALOG_CHARGE_CURRENT) * (3.3f / 4096.0f) / (CURRENT_SENSE_GAIN * R_SHUNT); -#else - status_message.charging_current = -1.0f; -#endif + status_message.charging_current = llhl_config.options.ignore_charging_current ? -1.0f : (float)analogRead(PIN_ANALOG_CHARGE_CURRENT) * (3.3f / 4096.0f) / (CURRENT_SENSE_GAIN * R_SHUNT); + status_message.status_bitmask = (status_message.status_bitmask & 0b11111011) | ((charging_allowed & 0b1) << 2); status_message.status_bitmask = (status_message.status_bitmask & 0b11011111) | ((sound_available & 0b1) << 5); From 5b18e4ac74f519182cb50d8186a7c46c2a4e5d54 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?J=C3=B6rg=20Ebeling?= Date: Sun, 20 Oct 2024 23:15:48 +0200 Subject: [PATCH 18/32] Finalize LittleFS --- Firmware/LowLevel/platformio.ini | 1 + Firmware/LowLevel/src/main.cpp | 27 +++++++++++++++------------ 2 files changed, 16 insertions(+), 12 deletions(-) diff --git a/Firmware/LowLevel/platformio.ini b/Firmware/LowLevel/platformio.ini index da73d020..8ba57d49 100644 --- a/Firmware/LowLevel/platformio.ini +++ b/Firmware/LowLevel/platformio.ini @@ -18,6 +18,7 @@ platform = https://github.com/maxgerhardt/platform-raspberrypi.git board = pico framework = arduino board_build.core = earlephilhower +board_build.filesystem_size = 64k lib_deps = Wire diff --git a/Firmware/LowLevel/src/main.cpp b/Firmware/LowLevel/src/main.cpp index 6d1e71d6..cb01b933 100644 --- a/Firmware/LowLevel/src/main.cpp +++ b/Firmware/LowLevel/src/main.cpp @@ -423,10 +423,6 @@ void setup() { UISerial.setStream(&UI1_SERIAL); UISerial.setPacketHandler(&onUIPacketReceived); - // Initialize flash and try to read config - LittleFS.begin(); - readConfigFromFlash(); - /* * IMU INITIALIZATION */ @@ -470,6 +466,13 @@ void setup() { status_message.status_bitmask |= 1; + rp2040.resumeOtherCore(); + + // Initialize flash and try to read config. + // ATTENTION: LittleFS needs other core (at least for initial format)! + LittleFS.begin(); + readConfigFromFlash(); + #ifdef ENABLE_SOUND_MODULE p.neoPixelSetValue(0, 0, 255, 255, true); @@ -489,8 +492,6 @@ void setup() { } #endif - rp2040.resumeOtherCore(); - // Cover UI board clear all LEDs leds_message.type = Set_LEDs; leds_message.leds = 0; @@ -818,12 +819,14 @@ void sendUIMessage(void *message, size_t size) { } void saveConfigToFlash() { - uint16_t crc = CRC16.ccitt((const uint8_t*) &llhl_config, sizeof(llhl_config)); + uint16_t crc = CRC16.ccitt((const uint8_t *)&llhl_config, sizeof(llhl_config)); if (crc == config_crc_in_flash) return; File f = LittleFS.open(CONFIG_FILENAME, "w"); - f.write((const uint8_t*) &llhl_config, sizeof(llhl_config)); - f.write((const uint8_t*) &crc, 2); + if (!f) return; + + f.write((const uint8_t *)&llhl_config, sizeof(llhl_config)); + f.write((const uint8_t *)&crc, 2); f.close(); } @@ -839,9 +842,9 @@ void readConfigFromFlash() { } // read config - uint8_t *buffer = (uint8_t *)malloc(f.size()); - if (buffer == NULL) - return; + uint8_t *buffer = (uint8_t *)malloc(size); + if (buffer == NULL) return; + f.read(buffer, size); f.close(); From 859de1b8cf1b3aa31794b3564217c6c3bbf87959 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?J=C3=B6rg=20Ebeling?= Date: Tue, 22 Oct 2024 22:16:38 +0200 Subject: [PATCH 19/32] Finish new flexible hall implementation --- Firmware/LowLevel/src/datatypes.h | 58 +++++------ Firmware/LowLevel/src/main.cpp | 154 ++++++++++++++++++------------ 2 files changed, 119 insertions(+), 93 deletions(-) diff --git a/Firmware/LowLevel/src/datatypes.h b/Firmware/LowLevel/src/datatypes.h index 98c43503..81efdcf1 100644 --- a/Firmware/LowLevel/src/datatypes.h +++ b/Firmware/LowLevel/src/datatypes.h @@ -34,21 +34,17 @@ enum HighLevelMode { MODE_RECORDING = 3 // ROS connected, Manual mode during recording etc }; -#define LL_EMERGENCY_BIT_LATCH 0b00000001 -#define LL_EMERGENCY_BIT_HALL1 0b00001000 // Lift1 -#define LL_EMERGENCY_BIT_HALL2 0b00010000 // Lift2 -#define LL_EMERGENCY_BIT_HALL3 0b00000010 // Stop1 -#define LL_EMERGENCY_BIT_HALL4 0b00000100 // Stop2 - -#define LL_EMERGENCY_BIT_LIFT1 LL_EMERGENCY_BIT_HALL1 -#define LL_EMERGENCY_BIT_LIFT2 LL_EMERGENCY_BIT_HALL2 -#define LL_EMERGENCY_BITS_LIFT (LL_EMERGENCY_BIT_LIFT1 | LL_EMERGENCY_BIT_LIFT2) -#define LL_EMERGENCY_BIT_STOP1 LL_EMERGENCY_BIT_HALL3 -#define LL_EMERGENCY_BIT_STOP2 LL_EMERGENCY_BIT_HALL4 -#define LL_EMERGENCY_BITS_STOP (LL_EMERGENCY_BIT_STOP1 | LL_EMERGENCY_BIT_STOP2) - -#define LIFT1_IS_INVERTED 0 -#define LIFT2_IS_INVERTED 0 +#define LL_EMERGENCY_BIT_LATCH (1 << 0) +#define LL_EMERGENCY_BIT_LIFT (1 << 1) // Lift (or tilt) +#define LL_EMERGENCY_BIT_STOP (1 << 2) // Stop + +// Need the old emergency_bitmask definition because CoverUI send it +#define LL_EMERGENCY_BIT_CU_LIFT 0b00001000 // LIFT | LIFTX (up to CoverUI FW 2.0x) +#define LL_EMERGENCY_BIT_CU_BUMP 0b00010000 // LBUMP | RBUMP (up to CoverUI FW 2.0x) +#define LL_EMERGENCY_BIT_CU_STOP1 0b00000010 // Stop1 +#define LL_EMERGENCY_BIT_CU_STOP2 0b00000100 // Stop2 +#define LL_EMERGENCY_BIT_CU_LIFTX 0b00100000 // CoverUI-LIFTX (as of CoverUI FW 2.1x) +#define LL_EMERGENCY_BIT_CU_RBUMP 0b01000000 // CoverUI-RBUMP (as of CoverUI FW 2.1x) #define LL_STATUS_BIT_UI_AVAIL 0b10000000 @@ -70,11 +66,8 @@ struct ll_status { float uss_ranges_m[5]; // Emergency bitmask: // Bit 0: Emergency latch - // Bit 1: Emergency/Hall 3 (Stop1) active - // Bit 2: Emergency/Hall 4 (Stop2) active - // Bit 3: Emergency/Hall 1 (Lift1) active - // Bit 4: Emergency/Hall 2 (Lift2) active - // Bit 5: Not an emergency but probably usable for pause via SA Handle? + // Bit 1: Emergency/Lift (or tilt) + // Bit 2: Emergency/Stop uint8_t emergency_bitmask; // Charge voltage float v_charge; @@ -150,19 +143,13 @@ enum class HallMode : unsigned int { OFF = 0, LIFT_TILT, // Wheel lifted and/or wheels tilted functionality STOP, // Stop mower - PAUSE, // Pause the mower (not yet implemented in ROS) UNDEFINED // This is used by foreign side to inform that it doesn't has a configuration for this sensor }; -enum class HallLevel : unsigned int { - ACTIVE_LOW = 0, // If Hall-Sensor (or button) is active/triggered we've this level on our GPIO - ACTIVE_HIGH -}; - #pragma pack(push, 1) struct HallConfig { - HallMode mode : 3; - HallLevel level : 1; + HallMode mode : 3; // 1 bit reserved + bool active_low : 1; } __attribute__((packed)); #pragma pack(pop) @@ -189,11 +176,16 @@ struct ll_high_level_config { iso639_1 language = {'e', 'n'}; // ISO 639-1 (2-char) language code (en, de, ...) uint8_t volume = 80; // Volume (0-100%) feedback (if directly changed i.e. via CoverUI or WebApp) (0xff = do not change) HallConfig hall_configs[MAX_HALL_INPUTS] = { - {HallMode::LIFT_TILT, HallLevel::ACTIVE_LOW}, // [0] OM Hall-1 input (Lift1) - {HallMode::LIFT_TILT, HallLevel::ACTIVE_LOW}, // [1] OM Hall-2 input (Lift2) - {HallMode::STOP, HallLevel::ACTIVE_LOW}, // [2] OM Hall-3 input (Stop1) - {HallMode::STOP, HallLevel::ACTIVE_LOW}, // [3] OM Hall-4 input (Stop2) - // [4] Stock-CoverUI-1 ... [9] Stock-CoverUI-6 default to off + {HallMode::LIFT_TILT, true}, // [0] OM Hall-1 input (Lift1) = YF-C500 default + {HallMode::LIFT_TILT, true}, // [1] OM Hall-2 input (Lift2) = YF-C500 default + {HallMode::STOP, true}, // [2] OM Hall-3 input (Stop1) = YF-C500 default + {HallMode::STOP, true}, // [3] OM Hall-4 input (Stop2) = YF-C500 default + //{HallMode::LIFT_TILT, false}, // [4] CoverUI-LIFT | LIFTX (up to CoverUI FW 2.0x) + //{HallMode::LIFT_TILT, false}, // [5] CoverUI-LIFTX (as of CoverUI FW 2.1x) + //{HallMode::LIFT_TILT, false}, // [6] CoverUI-LBUMP | RBUMP (up to CoverUI FW 2.0x) + //{HallMode::LIFT_TILT, false}, // [7] CoverUI-RBUMP (as of CoverUI FW 2.1x) + //{HallMode::STOP, false}, // [8] CoverUI-Stop1 + //{HallMode::STOP, false}, // [9] CoverUI-Stop2 }; // INFO: Before adding a new member here: Decide if and how much hall_configs spares do we like to have diff --git a/Firmware/LowLevel/src/main.cpp b/Firmware/LowLevel/src/main.cpp index cb01b933..674ca810 100644 --- a/Firmware/LowLevel/src/main.cpp +++ b/Firmware/LowLevel/src/main.cpp @@ -19,6 +19,7 @@ #include #include #include +#include #include "datatypes.h" #include "imu.h" @@ -123,6 +124,23 @@ uint16_t config_crc_in_flash = 0; struct ll_high_level_config llhl_config; // LL/HL configuration (is initialized with YF-C500 defaults) static_assert(sizeof(ConfigOptions) == 1, "Enlarging struct ConfigOption to a sizeof > 1 will break packet compatibilty"); +// Hall input sources, same order as in ll_high_level_config.hall_configs +std::function halls[MAX_HALL_INPUTS] = { + []() { return gpio_get(PIN_EMERGENCY_1); }, // OM-Hall-1 (default Lift1) + []() { return gpio_get(PIN_EMERGENCY_2); }, // OM-Hall-2 (default Lift2) + []() { return gpio_get(PIN_EMERGENCY_3); }, // OM-Hall-3 (default Stop1) + []() { return gpio_get(PIN_EMERGENCY_4); }, // OM-Hall-4 (default Stop2) + []() { return stock_ui_emergency_state & LL_EMERGENCY_BIT_CU_LIFT; }, // CoverUI-LIFT | LIFTX (up to CoverUI FW 2.0x) + []() { return stock_ui_emergency_state & LL_EMERGENCY_BIT_CU_LIFTX; }, // CoverUI-LIFTX (as of CoverUI FW 2.1x) + []() { return stock_ui_emergency_state & LL_EMERGENCY_BIT_CU_BUMP; }, // CoverUI-LBUMP | RBUMP (up to CoverUI FW 2.0x) + []() { return stock_ui_emergency_state & LL_EMERGENCY_BIT_CU_RBUMP; }, // CoverUI-RBUMP (as of CoverUI FW 2.1x) + []() { return stock_ui_emergency_state & LL_EMERGENCY_BIT_CU_STOP1; }, // CoverUI-Stop1 + []() { return stock_ui_emergency_state & LL_EMERGENCY_BIT_CU_STOP2; }, // CoverUI-Stop2 +}; +// Instead of iterating constantly over all halls, we use these compacted ones, whose contain the halls index of the used ones +uint8_t stop_halls[MAX_HALL_INPUTS] = {}; +uint8_t lift_halls[MAX_HALL_INPUTS] = {}; + void sendMessage(void *message, size_t size); void sendUIMessage(void *message, size_t size); void onPacketReceived(const uint8_t *buffer, size_t size); @@ -138,67 +156,59 @@ void setRaspiPower(bool power) { } void updateEmergency() { - // FIXME: Implement new hall_configs - if (millis() - last_heartbeat_millis > HEARTBEAT_MILLIS) { emergency_latch = true; ROS_running = false; } uint8_t last_emergency = status_message.emergency_bitmask & LL_EMERGENCY_BIT_LATCH; - - // Read & assign emergencies in the same manner as in ll_status.emergency_bitmask - uint8_t emergency_read = !gpio_get(PIN_EMERGENCY_3) << 1 | // Stop1 - !gpio_get(PIN_EMERGENCY_4) << 2 | // Stop2 - !gpio_get(PIN_EMERGENCY_1) << 3 | // Lift1 - !gpio_get(PIN_EMERGENCY_2) << 4 | // Lift2 - stock_ui_emergency_state; // OR with StockUI emergency uint8_t emergency_state = 0; - // Some mowers have the logic level inverted, fix this... - emergency_read = emergency_read ^ (LL_EMERGENCY_BIT_LIFT1 * LIFT1_IS_INVERTED); - emergency_read = emergency_read ^ (LL_EMERGENCY_BIT_LIFT2 * LIFT2_IS_INVERTED); + // Check all "stop" mode emergency inputs (halls) + bool stop_pressed = false; + size_t i; + for (i = 0; i < MAX_HALL_INPUTS; i++) { + if (stop_halls[i] == 0xff) break; // End marker reached + stop_pressed = halls[stop_halls[i]]() ^ llhl_config.hall_configs[stop_halls[i]].active_low; // Get hall value and apply active_low level (invert) + if (stop_pressed) break; // Break at first detected stop + } // Handle emergency "Stop" buttons - if (emergency_read & LL_EMERGENCY_BITS_STOP) { - // If we just pressed, store the timestamp - if (button_emergency_started == 0) { - button_emergency_started = millis(); - } + if (stop_pressed) { + if (button_emergency_started == 0) button_emergency_started = millis(); // If we just pressed, store the timestamp } else { - // Not pressed, reset the time - button_emergency_started = 0; + button_emergency_started = 0; // Not pressed, reset the time + } + if (button_emergency_started > 0 && (millis() - button_emergency_started) >= BUTTON_EMERGENCY_MILLIS) { + emergency_state |= LL_EMERGENCY_BIT_STOP; } - if (button_emergency_started > 0 && (millis() - button_emergency_started) >= BUTTON_EMERGENCY_MILLIS) - { - emergency_state |= (emergency_read & LL_EMERGENCY_BITS_STOP); + // Check all "lifted" mode emergency inputs (halls) + int num_lifted = 0; + for (i = 0; i < MAX_HALL_INPUTS; i++) { + if (lift_halls[i] == 0xff) break; // End marker reached + if (halls[lift_halls[i]]() ^ llhl_config.hall_configs[lift_halls[i]].active_low) // Get hall value and apply active_low level (invert) + num_lifted++; + if (num_lifted >= 2) break; // Break once two wheels are lifted } - // Handle lifted (both wheels are lifted) - if ((emergency_read & LL_EMERGENCY_BITS_LIFT) == LL_EMERGENCY_BITS_LIFT) { - // If we just lifted, store the timestamp - if (lift_emergency_started == 0) { - lift_emergency_started = millis(); - } + // Handle lifted (>=2 wheels are lifted) + if (num_lifted >= 2) { + if (lift_emergency_started == 0) lift_emergency_started = millis(); // If we just lifted, store the timestamp } else { - // Not lifted, reset the time - lift_emergency_started = 0; + lift_emergency_started = 0; // Not lifted, reset the time } - // Handle tilted (one wheel is lifted) - if (emergency_read & LL_EMERGENCY_BITS_LIFT) { - // If we just tilted, store the timestamp - if (tilt_emergency_started == 0) { - tilt_emergency_started = millis(); - } + // Handle tilted (at least one wheel is lifted) + if (num_lifted >= 1) { + if (tilt_emergency_started == 0) tilt_emergency_started = millis(); // If we just tilted, store the timestamp } else { - // Not tilted, reset the time - tilt_emergency_started = 0; + tilt_emergency_started = 0; // Not tilted, reset the time } + // Evaluate lift & tilt periods if ((llhl_config.lift_period > 0 && lift_emergency_started > 0 && (millis() - lift_emergency_started) >= llhl_config.lift_period) || (llhl_config.tilt_period > 0 && tilt_emergency_started > 0 && (millis() - tilt_emergency_started) >= llhl_config.tilt_period)) { - emergency_state |= (emergency_read & LL_EMERGENCY_BITS_LIFT); + emergency_state |= LL_EMERGENCY_BIT_LIFT; } if (emergency_state || emergency_latch) { @@ -293,9 +303,9 @@ void manageUILEDS() { } // Show Info mower lifted or stop button pressed - if (status_message.emergency_bitmask & LL_EMERGENCY_BITS_STOP) { + if (status_message.emergency_bitmask & LL_EMERGENCY_BIT_STOP) { setLed(leds_message, LED_MOWER_LIFTED, LED_blink_fast); - } else if (status_message.emergency_bitmask & LL_EMERGENCY_BITS_LIFT) { + } else if (status_message.emergency_bitmask & LL_EMERGENCY_BIT_LIFT) { setLed(leds_message, LED_MOWER_LIFTED, LED_blink_slow); } else if (status_message.emergency_bitmask & LL_EMERGENCY_BIT_LATCH) { setLed(leds_message, LED_MOWER_LIFTED, LED_on); @@ -562,38 +572,62 @@ void sendConfigMessage(const uint8_t pkt_type) { free(msg); } +/** + * @brief applyConfig applies those members who are not undefined/unknown. + * This function get called either when receiving a ll_high_level_config packet from HL, or during boot after read from LittleFS + * @param buffer + * @param size + */ void applyConfig(const uint8_t *buffer, const size_t size) { - // This is a flexible length packet where the size may vary when ll_high_level_config struct got enhanced only on one side. + // This is a flexible length packet where the size may vary when ll_high_level_config struct get enhanced only on one side. // If payload size is larger than our struct size, ensure that we only copy those we know of = our struct size. // If payload size is smaller than our struct size, copy only the payload we got, but ensure that the unsent member(s) have reasonable defaults. size_t payload_size = min(sizeof(ll_high_level_config), size - 2); // exclude crc - // Use a temporary config for easier sanity adaption and copy our live config, which has at least reasonable defaults. - // The live config copy ensures that we've reasonable values for the case that HL config struct is older (smaller) than ours. - auto hl_config = llhl_config; + // Use a temporary config for easier sanity adaption and copy to our live config, which has reasonable defaults. + // The initializing live config copy ensures that we've reasonable values for the case that HL config struct is older (smaller) than ours. + auto rcv_config = llhl_config; // Copy payload to temporary config - memcpy(&hl_config, buffer, payload_size); + memcpy(&rcv_config, buffer, payload_size); // HL always force these - llhl_config.options = hl_config.options; - strncpy(llhl_config.language, hl_config.language, 2); + llhl_config.options = rcv_config.options; + strncpy(llhl_config.language, rcv_config.language, 2); // Take over only those HL members who are not "undefined/unknown" - if (hl_config.rain_threshold != 0xffff) llhl_config.rain_threshold = hl_config.rain_threshold; - if (hl_config.v_charge_cutoff >= 0) llhl_config.v_charge_cutoff = min(hl_config.v_charge_cutoff, 36.0f); // Rated max. limited by MAX20405 - if (hl_config.i_charge_cutoff >= 0) llhl_config.i_charge_cutoff = min(hl_config.i_charge_cutoff, 5.0f); // Absolute max. limited by D2/D3 Schottky - if (hl_config.v_battery_cutoff >= 0) llhl_config.v_battery_cutoff = hl_config.v_battery_cutoff; - if (hl_config.v_battery_empty >= 0) llhl_config.v_battery_empty = hl_config.v_battery_empty; - if (hl_config.v_battery_full >= 0) llhl_config.v_battery_full = hl_config.v_battery_full; - if (hl_config.lift_period != 0xffff) llhl_config.lift_period = hl_config.lift_period; - if (hl_config.tilt_period != 0xffff) llhl_config.tilt_period = hl_config.tilt_period; - if (hl_config.volume != 0xff) llhl_config.volume = hl_config.volume; + if (rcv_config.rain_threshold != 0xffff) llhl_config.rain_threshold = rcv_config.rain_threshold; + if (rcv_config.v_charge_cutoff >= 0) llhl_config.v_charge_cutoff = min(rcv_config.v_charge_cutoff, 36.0f); // Rated max. limited by MAX20405 + if (rcv_config.i_charge_cutoff >= 0) llhl_config.i_charge_cutoff = min(rcv_config.i_charge_cutoff, 5.0f); // Absolute max. limited by D2/D3 Schottky + if (rcv_config.v_battery_cutoff >= 0) llhl_config.v_battery_cutoff = rcv_config.v_battery_cutoff; + if (rcv_config.v_battery_empty >= 0) llhl_config.v_battery_empty = rcv_config.v_battery_empty; + if (rcv_config.v_battery_full >= 0) llhl_config.v_battery_full = rcv_config.v_battery_full; + if (rcv_config.lift_period != 0xffff) llhl_config.lift_period = rcv_config.lift_period; + if (rcv_config.tilt_period != 0xffff) llhl_config.tilt_period = rcv_config.tilt_period; + if (rcv_config.volume != 0xff) llhl_config.volume = rcv_config.volume; // Take over those hall inputs which are not undefined - for (size_t i = 0; i < MAX_HALL_INPUTS; i++) - if (hl_config.hall_configs[i].mode != HallMode::UNDEFINED) - llhl_config.hall_configs[i] = hl_config.hall_configs[i]; + for (size_t i = 0; i < MAX_HALL_INPUTS; i++) { + if (rcv_config.hall_configs[i].mode != HallMode::UNDEFINED) + llhl_config.hall_configs[i] = rcv_config.hall_configs[i]; + } + + // Apply active Emergency/Hall configurations to our compacted stop/lift-hall arrays which get used by updateEmergency() + uint8_t stop_hall_idx = 0, lift_hall_idx = 0; + for (size_t i = 0; i < MAX_HALL_INPUTS; i++) { + switch (llhl_config.hall_configs[i].mode) { + case HallMode::LIFT_TILT: + lift_halls[lift_hall_idx] = i; + lift_hall_idx++; + break; + case HallMode::STOP: + stop_halls[stop_hall_idx] = i; + stop_hall_idx++; + break; + } + } + lift_halls[lift_hall_idx] = 0xff; // End of lift halls marker + stop_halls[stop_hall_idx] = 0xff; // End of stop halls marker } void onPacketReceived(const uint8_t *buffer, size_t size) { From 4135fa54e9692b0332f3883d7976e3b39aab89c0 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?J=C3=B6rg=20Ebeling?= Date: Tue, 22 Oct 2024 22:35:32 +0200 Subject: [PATCH 20/32] Remove IGNORE_CHARGING_CURRENT builds from artifacts --- .github/workflows/ci.yaml | 21 --------------------- 1 file changed, 21 deletions(-) diff --git a/.github/workflows/ci.yaml b/.github/workflows/ci.yaml index 791f9cf1..6164143f 100644 --- a/.github/workflows/ci.yaml +++ b/.github/workflows/ci.yaml @@ -116,27 +116,6 @@ jobs: cp Firmware/LowLevel/.pio/build/0_9_X_WT901_INSTEAD_OF_SOUND/firmware.elf ./artifacts/0_9_X_WT901_INSTEAD_OF_SOUND cp Firmware/LowLevel/.pio/build/0_9_X_WT901_INSTEAD_OF_SOUND/firmware.uf2 ./artifacts/0_9_X_WT901_INSTEAD_OF_SOUND - mkdir ./artifacts/0_13_X_IGNORE_CHARGING_CURRENT - cp Firmware/LowLevel/.pio/build/0_13_X_IGNORE_CHARGING_CURRENT/firmware.elf ./artifacts/0_13_X_IGNORE_CHARGING_CURRENT - cp Firmware/LowLevel/.pio/build/0_13_X_IGNORE_CHARGING_CURRENT/firmware.uf2 ./artifacts/0_13_X_IGNORE_CHARGING_CURRENT - - mkdir ./artifacts/0_12_X_IGNORE_CHARGING_CURRENT - cp Firmware/LowLevel/.pio/build/0_12_X_IGNORE_CHARGING_CURRENT/firmware.elf ./artifacts/0_12_X_IGNORE_CHARGING_CURRENT - cp Firmware/LowLevel/.pio/build/0_12_X_IGNORE_CHARGING_CURRENT/firmware.uf2 ./artifacts/0_12_X_IGNORE_CHARGING_CURRENT - - mkdir ./artifacts/0_11_X_WT901_IGNORE_CHARGING_CURRENT - cp Firmware/LowLevel/.pio/build/0_11_X_WT901_IGNORE_CHARGING_CURRENT/firmware.elf ./artifacts/0_11_X_WT901_IGNORE_CHARGING_CURRENT - cp Firmware/LowLevel/.pio/build/0_11_X_WT901_IGNORE_CHARGING_CURRENT/firmware.uf2 ./artifacts/0_11_X_WT901_IGNORE_CHARGING_CURRENT - - mkdir ./artifacts/0_10_X_WT901_IGNORE_CHARGING_CURRENT - cp Firmware/LowLevel/.pio/build/0_10_X_WT901_IGNORE_CHARGING_CURRENT/firmware.elf ./artifacts/0_10_X_WT901_IGNORE_CHARGING_CURRENT - cp Firmware/LowLevel/.pio/build/0_10_X_WT901_IGNORE_CHARGING_CURRENT/firmware.uf2 ./artifacts/0_10_X_WT901_IGNORE_CHARGING_CURRENT - - mkdir ./artifacts/0_9_X_WT901_IGNORE_CHARGING_CURRENT - cp Firmware/LowLevel/.pio/build/0_9_X_WT901_IGNORE_CHARGING_CURRENT/firmware.elf ./artifacts/0_9_X_WT901_IGNORE_CHARGING_CURRENT - cp Firmware/LowLevel/.pio/build/0_9_X_WT901_IGNORE_CHARGING_CURRENT/firmware.uf2 ./artifacts/0_9_X_WT901_IGNORE_CHARGING_CURRENT - - - name: Upload Artifacts uses: actions/upload-artifact@v4 with: From fe8e829db3447b803d3251297f5e0e51f4c4d189 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?J=C3=B6rg=20Ebeling?= Date: Tue, 22 Oct 2024 23:12:29 +0200 Subject: [PATCH 21/32] Make halls const --- Firmware/LowLevel/src/main.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Firmware/LowLevel/src/main.cpp b/Firmware/LowLevel/src/main.cpp index 674ca810..3be6e5ed 100644 --- a/Firmware/LowLevel/src/main.cpp +++ b/Firmware/LowLevel/src/main.cpp @@ -125,7 +125,7 @@ struct ll_high_level_config llhl_config; // LL/HL configuration (is initialized static_assert(sizeof(ConfigOptions) == 1, "Enlarging struct ConfigOption to a sizeof > 1 will break packet compatibilty"); // Hall input sources, same order as in ll_high_level_config.hall_configs -std::function halls[MAX_HALL_INPUTS] = { +const std::function halls[MAX_HALL_INPUTS] = { []() { return gpio_get(PIN_EMERGENCY_1); }, // OM-Hall-1 (default Lift1) []() { return gpio_get(PIN_EMERGENCY_2); }, // OM-Hall-2 (default Lift2) []() { return gpio_get(PIN_EMERGENCY_3); }, // OM-Hall-3 (default Stop1) From 32d65767525a9bfa3eedaf12b49fb423657ce2b2 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?J=C3=B6rg=20Ebeling?= Date: Thu, 24 Oct 2024 21:01:16 +0200 Subject: [PATCH 22/32] Apply received packet on default-config (instead of live-config) --- Firmware/LowLevel/src/datatypes.h | 2 +- Firmware/LowLevel/src/main.cpp | 54 ++++++++++++++++++------------- 2 files changed, 32 insertions(+), 24 deletions(-) diff --git a/Firmware/LowLevel/src/datatypes.h b/Firmware/LowLevel/src/datatypes.h index 81efdcf1..5fcda07b 100644 --- a/Firmware/LowLevel/src/datatypes.h +++ b/Firmware/LowLevel/src/datatypes.h @@ -170,7 +170,7 @@ struct ll_high_level_config { float v_battery_cutoff = 29.0f; // Protective max. battery voltage before charging get switched off (-1 = unknown) float v_battery_empty = 21.7f + 0.3f; // Empty battery voltage used for % calc of capacity (-1 = unknown) float v_battery_full = 28.7f - 0.3f; // Full battery voltage used for % calc of capacity (-1 = unknown) - uint16_t lift_period = 100; // Period (ms) for both wheels to be lifted in order to count as emergency (0 = disable, 0xFFFF = unknown). This is to filter uneven ground + uint16_t lift_period = 100; // Period (ms) for >=2 wheels to be lifted in order to count as emergency (0 = disable, 0xFFFF = unknown). This is to filter uneven ground uint16_t tilt_period = 2500; // Period (ms) for a single wheel to be lifted in order to count as emergency (0 = disable, 0xFFFF = unknown). This is to filter uneven ground float shutdown_esc_max_pitch = 0.0f; // Do not shutdown ESCs if absolute pitch angle is greater than this (0 = disable, 0xffff = unknown) (to be implemented) iso639_1 language = {'e', 'n'}; // ISO 639-1 (2-char) language code (en, de, ...) diff --git a/Firmware/LowLevel/src/main.cpp b/Firmware/LowLevel/src/main.cpp index 3be6e5ed..9b364440 100644 --- a/Firmware/LowLevel/src/main.cpp +++ b/Firmware/LowLevel/src/main.cpp @@ -584,38 +584,44 @@ void applyConfig(const uint8_t *buffer, const size_t size) { // If payload size is smaller than our struct size, copy only the payload we got, but ensure that the unsent member(s) have reasonable defaults. size_t payload_size = min(sizeof(ll_high_level_config), size - 2); // exclude crc - // Use a temporary config for easier sanity adaption and copy to our live config, which has reasonable defaults. - // The initializing live config copy ensures that we've reasonable values for the case that HL config struct is older (smaller) than ours. - auto rcv_config = llhl_config; - - // Copy payload to temporary config - memcpy(&rcv_config, buffer, payload_size); - - // HL always force these - llhl_config.options = rcv_config.options; - strncpy(llhl_config.language, rcv_config.language, 2); - - // Take over only those HL members who are not "undefined/unknown" - if (rcv_config.rain_threshold != 0xffff) llhl_config.rain_threshold = rcv_config.rain_threshold; - if (rcv_config.v_charge_cutoff >= 0) llhl_config.v_charge_cutoff = min(rcv_config.v_charge_cutoff, 36.0f); // Rated max. limited by MAX20405 - if (rcv_config.i_charge_cutoff >= 0) llhl_config.i_charge_cutoff = min(rcv_config.i_charge_cutoff, 5.0f); // Absolute max. limited by D2/D3 Schottky - if (rcv_config.v_battery_cutoff >= 0) llhl_config.v_battery_cutoff = rcv_config.v_battery_cutoff; - if (rcv_config.v_battery_empty >= 0) llhl_config.v_battery_empty = rcv_config.v_battery_empty; - if (rcv_config.v_battery_full >= 0) llhl_config.v_battery_full = rcv_config.v_battery_full; - if (rcv_config.lift_period != 0xffff) llhl_config.lift_period = rcv_config.lift_period; - if (rcv_config.tilt_period != 0xffff) llhl_config.tilt_period = rcv_config.tilt_period; - if (rcv_config.volume != 0xff) llhl_config.volume = rcv_config.volume; + // Use a temporary rcv_config for easier member access. + // If payload is smaller (older), struct already contains reasonable defaults. + ll_high_level_config rcv_config; + memcpy(&rcv_config, buffer, payload_size); // Copy payload to temporary config + + // Use a temporary new_config for save sanity adaption before copy to our live config. + // It's important to use a clean one with LL-default values, and not the current live llhl_config one, + // because we need to ensure that re-commented mower_config parameter get the LL-default value and not the last saved one! + ll_high_level_config new_config; + + // Take over of payload values. This could also be made the other way around, which would save the copy of the "leading" + // values, but I felt it's more secure to do it this way (in special for further packet enlargements) + + // HL always force these member + new_config.options = rcv_config.options; + strncpy(new_config.language, rcv_config.language, 2); + + // Take over only those (HL) values which are not "undefined/unknown" + if (rcv_config.rain_threshold != 0xffff) new_config.rain_threshold = rcv_config.rain_threshold; + if (rcv_config.v_charge_cutoff >= 0) new_config.v_charge_cutoff = min(rcv_config.v_charge_cutoff, 36.0f); // Rated max. limited by MAX20405 + if (rcv_config.i_charge_cutoff >= 0) new_config.i_charge_cutoff = min(rcv_config.i_charge_cutoff, 5.0f); // Absolute max. limited by D2/D3 Schottky + if (rcv_config.v_battery_cutoff >= 0) new_config.v_battery_cutoff = rcv_config.v_battery_cutoff; + if (rcv_config.v_battery_empty >= 0) new_config.v_battery_empty = rcv_config.v_battery_empty; + if (rcv_config.v_battery_full >= 0) new_config.v_battery_full = rcv_config.v_battery_full; + if (rcv_config.lift_period != 0xffff) new_config.lift_period = rcv_config.lift_period; + if (rcv_config.tilt_period != 0xffff) new_config.tilt_period = rcv_config.tilt_period; + if (rcv_config.volume != 0xff) new_config.volume = rcv_config.volume; // Take over those hall inputs which are not undefined for (size_t i = 0; i < MAX_HALL_INPUTS; i++) { if (rcv_config.hall_configs[i].mode != HallMode::UNDEFINED) - llhl_config.hall_configs[i] = rcv_config.hall_configs[i]; + new_config.hall_configs[i] = rcv_config.hall_configs[i]; } // Apply active Emergency/Hall configurations to our compacted stop/lift-hall arrays which get used by updateEmergency() uint8_t stop_hall_idx = 0, lift_hall_idx = 0; for (size_t i = 0; i < MAX_HALL_INPUTS; i++) { - switch (llhl_config.hall_configs[i].mode) { + switch (new_config.hall_configs[i].mode) { case HallMode::LIFT_TILT: lift_halls[lift_hall_idx] = i; lift_hall_idx++; @@ -628,6 +634,8 @@ void applyConfig(const uint8_t *buffer, const size_t size) { } lift_halls[lift_hall_idx] = 0xff; // End of lift halls marker stop_halls[stop_hall_idx] = 0xff; // End of stop halls marker + + llhl_config = new_config; // Make new config live } void onPacketReceived(const uint8_t *buffer, size_t size) { From 2328792b927b4a29314c01321062b9cac505baa9 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?J=C3=B6rg=20Ebeling?= Date: Thu, 24 Oct 2024 23:33:01 +0200 Subject: [PATCH 23/32] Add configurable (Stock-CoverUI) rain threshold --- Firmware/LowLevel/platformio.ini | 3 ++- Firmware/LowLevel/src/main.cpp | 2 +- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/Firmware/LowLevel/platformio.ini b/Firmware/LowLevel/platformio.ini index 8ba57d49..77178bc5 100644 --- a/Firmware/LowLevel/platformio.ini +++ b/Firmware/LowLevel/platformio.ini @@ -33,7 +33,8 @@ lib_deps = debug_tool = custom debug_init_break = debug_load_mode = always -debug_port = tcp:openmower.local:3333 +;debug_port = tcp:openmower.local:3333 +debug_port = tcp:dolly:3333 ; 133MHz board_build.f_cpu = 133000000L diff --git a/Firmware/LowLevel/src/main.cpp b/Firmware/LowLevel/src/main.cpp index 9b364440..87fb934e 100644 --- a/Firmware/LowLevel/src/main.cpp +++ b/Firmware/LowLevel/src/main.cpp @@ -551,7 +551,7 @@ void onUIPacketReceived(const uint8_t *buffer, size_t size) { else if (buffer[0] == Get_Rain && size == sizeof(struct msg_event_rain)) { struct msg_event_rain *msg = (struct msg_event_rain *)buffer; - stock_ui_rain = (msg->value < msg->threshold); + stock_ui_rain = (msg->value < llhl_config.rain_threshold); } else if (buffer[0] == Get_Subscribe && size == sizeof(struct msg_event_subscribe)) { From 21e5baf931140033b86ed60361c32544a02dbe41 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?J=C3=B6rg=20Ebeling?= Date: Sat, 26 Oct 2024 18:31:08 +0200 Subject: [PATCH 24/32] Change config packet IDs --- Firmware/LowLevel/src/datatypes.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Firmware/LowLevel/src/datatypes.h b/Firmware/LowLevel/src/datatypes.h index 5fcda07b..7b1a4b7e 100644 --- a/Firmware/LowLevel/src/datatypes.h +++ b/Firmware/LowLevel/src/datatypes.h @@ -23,8 +23,8 @@ #define PACKET_ID_LL_STATUS 1 #define PACKET_ID_LL_IMU 2 #define PACKET_ID_LL_UI_EVENT 3 -#define PACKET_ID_LL_HIGH_LEVEL_CONFIG_REQ 0x21 // ll_high_level_config and request config from receiver -#define PACKET_ID_LL_HIGH_LEVEL_CONFIG_RSP 0x22 // ll_high_level_config response +#define PACKET_ID_LL_HIGH_LEVEL_CONFIG_REQ 0x11 // ll_high_level_config and request config from receiver +#define PACKET_ID_LL_HIGH_LEVEL_CONFIG_RSP 0x12 // ll_high_level_config response #define PACKET_ID_LL_HEARTBEAT 0x42 #define PACKET_ID_LL_HIGH_LEVEL_STATE 0x43 From 12874d21c23cc8efa0e83a29d366d0ce8bd443b4 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?J=C3=B6rg=20Ebeling?= Date: Sat, 26 Oct 2024 21:13:33 +0200 Subject: [PATCH 25/32] Cleanup --- Firmware/LowLevel/platformio.ini | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/Firmware/LowLevel/platformio.ini b/Firmware/LowLevel/platformio.ini index 77178bc5..8ba57d49 100644 --- a/Firmware/LowLevel/platformio.ini +++ b/Firmware/LowLevel/platformio.ini @@ -33,8 +33,7 @@ lib_deps = debug_tool = custom debug_init_break = debug_load_mode = always -;debug_port = tcp:openmower.local:3333 -debug_port = tcp:dolly:3333 +debug_port = tcp:openmower.local:3333 ; 133MHz board_build.f_cpu = 133000000L From 485e0a8c926d2a2ef7065977a5dedf4ceecf211a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?J=C3=B6rg=20Ebeling?= Date: Mon, 28 Oct 2024 14:06:43 +0100 Subject: [PATCH 26/32] Cosmetic changes --- Firmware/LowLevel/src/datatypes.h | 30 +++++++++++++++++------------- Firmware/LowLevel/src/main.cpp | 15 +++++++-------- 2 files changed, 24 insertions(+), 21 deletions(-) diff --git a/Firmware/LowLevel/src/datatypes.h b/Firmware/LowLevel/src/datatypes.h index 7b1a4b7e..9a44a0e9 100644 --- a/Firmware/LowLevel/src/datatypes.h +++ b/Firmware/LowLevel/src/datatypes.h @@ -34,19 +34,22 @@ enum HighLevelMode { MODE_RECORDING = 3 // ROS connected, Manual mode during recording etc }; -#define LL_EMERGENCY_BIT_LATCH (1 << 0) -#define LL_EMERGENCY_BIT_LIFT (1 << 1) // Lift (or tilt) -#define LL_EMERGENCY_BIT_STOP (1 << 2) // Stop - -// Need the old emergency_bitmask definition because CoverUI send it -#define LL_EMERGENCY_BIT_CU_LIFT 0b00001000 // LIFT | LIFTX (up to CoverUI FW 2.0x) -#define LL_EMERGENCY_BIT_CU_BUMP 0b00010000 // LBUMP | RBUMP (up to CoverUI FW 2.0x) -#define LL_EMERGENCY_BIT_CU_STOP1 0b00000010 // Stop1 -#define LL_EMERGENCY_BIT_CU_STOP2 0b00000100 // Stop2 -#define LL_EMERGENCY_BIT_CU_LIFTX 0b00100000 // CoverUI-LIFTX (as of CoverUI FW 2.1x) -#define LL_EMERGENCY_BIT_CU_RBUMP 0b01000000 // CoverUI-RBUMP (as of CoverUI FW 2.1x) - -#define LL_STATUS_BIT_UI_AVAIL 0b10000000 +// clang-format off +#define LL_EMERGENCY_BIT_LATCH (1 << 0) // Any emergency latch +#define LL_EMERGENCY_BIT_STOP (1 << 1) // Stop +#define LL_EMERGENCY_BIT_LIFT (1 << 2) // Lift (or tilt) + +// CoverUI will stay with the old emergency_bitmask definition +#define LL_EMERGENCY_BIT_CU_LATCH (1 << 0) // Any emergency latch +#define LL_EMERGENCY_BIT_CU_STOP1 (1 << 1) // Stop1 +#define LL_EMERGENCY_BIT_CU_STOP2 (1 << 2) // Stop2 +#define LL_EMERGENCY_BIT_CU_LIFT (1 << 3) // LIFT | LIFTX (up to CoverUI FW 2.0x) +#define LL_EMERGENCY_BIT_CU_BUMP (1 << 4) // LBUMP | RBUMP (up to CoverUI FW 2.0x) +#define LL_EMERGENCY_BIT_CU_LIFTX (1 << 5) // CoverUI-LIFTX (as of CoverUI FW 2.1x) +#define LL_EMERGENCY_BIT_CU_RBUMP (1 << 6) // CoverUI-RBUMP (as of CoverUI FW 2.1x) + +#define LL_STATUS_BIT_UI_AVAIL (1 << 7) +// clang-format on #pragma pack(push, 1) struct ll_status { @@ -136,6 +139,7 @@ struct ConfigOptions { bool ignore_charging_current : 1; } __attribute__((packed)); #pragma pack(pop) +static_assert(sizeof(ConfigOptions) == 1, "Enlarging struct ConfigOption to a sizeof > 1 will break packet compatibilty"); typedef char iso639_1[2]; // Two char ISO 639-1 language code diff --git a/Firmware/LowLevel/src/main.cpp b/Firmware/LowLevel/src/main.cpp index 87fb934e..5f562cd4 100644 --- a/Firmware/LowLevel/src/main.cpp +++ b/Firmware/LowLevel/src/main.cpp @@ -122,7 +122,6 @@ uint16_t ui_interval = 1000; // UI send msg (LED/State) interval ( #define CONFIG_FILENAME "/openmower.cfg" // Where our llhl_config get saved in LittleFS (flash) uint16_t config_crc_in_flash = 0; struct ll_high_level_config llhl_config; // LL/HL configuration (is initialized with YF-C500 defaults) -static_assert(sizeof(ConfigOptions) == 1, "Enlarging struct ConfigOption to a sizeof > 1 will break packet compatibilty"); // Hall input sources, same order as in ll_high_level_config.hall_configs const std::function halls[MAX_HALL_INPUTS] = { @@ -566,9 +565,9 @@ void sendConfigMessage(const uint8_t pkt_type) { uint8_t *msg = (uint8_t *)malloc(msg_size); if (msg == NULL) return; - *msg = pkt_type; + msg[0] = pkt_type; memcpy(msg + 1, &llhl_config, sizeof(struct ll_high_level_config)); // Copy our live config into the message, behind type - sendMessage(msg, msg_size); + sendMessage(msg, msg_size); // sendMessage() also calculate the packet CRC free(msg); } @@ -576,13 +575,13 @@ void sendConfigMessage(const uint8_t pkt_type) { * @brief applyConfig applies those members who are not undefined/unknown. * This function get called either when receiving a ll_high_level_config packet from HL, or during boot after read from LittleFS * @param buffer - * @param size + * @param size of buffer (without packet type nor CRC) */ void applyConfig(const uint8_t *buffer, const size_t size) { // This is a flexible length packet where the size may vary when ll_high_level_config struct get enhanced only on one side. - // If payload size is larger than our struct size, ensure that we only copy those we know of = our struct size. + // If payload size is larger than our struct size, ensure that we only copy those we know of (which is our struct size). // If payload size is smaller than our struct size, copy only the payload we got, but ensure that the unsent member(s) have reasonable defaults. - size_t payload_size = min(sizeof(ll_high_level_config), size - 2); // exclude crc + size_t payload_size = min(sizeof(ll_high_level_config), size); // Use a temporary rcv_config for easier member access. // If payload is smaller (older), struct already contains reasonable defaults. @@ -670,7 +669,7 @@ void onPacketReceived(const uint8_t *buffer, size_t size) { // copy the state last_high_level_state = *((struct ll_high_level_state *) buffer); } else if (buffer[0] == PACKET_ID_LL_HIGH_LEVEL_CONFIG_REQ || buffer[0] == PACKET_ID_LL_HIGH_LEVEL_CONFIG_RSP) { - applyConfig(buffer + 1, size - 1); // Skip type + applyConfig(buffer + 1, size - 3); // Skip packet- type and CRC // Store in flash saveConfigToFlash(); @@ -898,6 +897,6 @@ void readConfigFromFlash() { return; config_crc_in_flash = crc; - applyConfig(buffer, size); + applyConfig(buffer, size - 2); // Skip CRC free(buffer); } From 7ba963dde515997d35423a776b66065e493305e7 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?J=C3=B6rg=20Ebeling?= Date: Mon, 28 Oct 2024 23:10:41 +0100 Subject: [PATCH 27/32] Store config packet instead of effective config --- Firmware/LowLevel/src/main.cpp | 32 +++++++++++++------------------- 1 file changed, 13 insertions(+), 19 deletions(-) diff --git a/Firmware/LowLevel/src/main.cpp b/Firmware/LowLevel/src/main.cpp index 5f562cd4..ee554559 100644 --- a/Firmware/LowLevel/src/main.cpp +++ b/Firmware/LowLevel/src/main.cpp @@ -145,7 +145,6 @@ void sendUIMessage(void *message, size_t size); void onPacketReceived(const uint8_t *buffer, size_t size); void onUIPacketReceived(const uint8_t *buffer, size_t size); void manageUISubscriptions(); -void saveConfigToFlash(); void readConfigFromFlash(); void setRaspiPower(bool power) { @@ -671,11 +670,18 @@ void onPacketReceived(const uint8_t *buffer, size_t size) { } else if (buffer[0] == PACKET_ID_LL_HIGH_LEVEL_CONFIG_REQ || buffer[0] == PACKET_ID_LL_HIGH_LEVEL_CONFIG_RSP) { applyConfig(buffer + 1, size - 3); // Skip packet- type and CRC - // Store in flash - saveConfigToFlash(); - + // Response if requested (before save, to ensure REQ/RSP timing) if (buffer[0] == PACKET_ID_LL_HIGH_LEVEL_CONFIG_REQ) sendConfigMessage(PACKET_ID_LL_HIGH_LEVEL_CONFIG_RSP); // Other side requested a config response + + // Store the whole received packet in flash and not the live (applied) config. This has the following benefits: + // - We're free to change ll_high_level_config defaults in future without fiddling with already stored ones + // - Reuse the already calculated and validated CRC + if (crc == config_crc_in_flash) return; // Protect wear leveling + File f = LittleFS.open(CONFIG_FILENAME, "w"); + if (!f) return; + if (f.write(buffer, size) == size) config_crc_in_flash = crc; + f.close(); } } @@ -859,25 +865,13 @@ void sendUIMessage(void *message, size_t size) { UISerial.send((uint8_t *) message, size); } -void saveConfigToFlash() { - uint16_t crc = CRC16.ccitt((const uint8_t *)&llhl_config, sizeof(llhl_config)); - if (crc == config_crc_in_flash) return; - - File f = LittleFS.open(CONFIG_FILENAME, "w"); - if (!f) return; - - f.write((const uint8_t *)&llhl_config, sizeof(llhl_config)); - f.write((const uint8_t *)&crc, 2); - f.close(); -} - void readConfigFromFlash() { File f = LittleFS.open(CONFIG_FILENAME, "r"); if (!f) return; - // sanity check for CRC to work (1 data, 2 CRC) + // sanity check for CRC to work (1 type, 1 data, 2 CRC) const size_t size = f.size(); - if (size < 3) { + if (size < 4) { f.close(); return; } @@ -897,6 +891,6 @@ void readConfigFromFlash() { return; config_crc_in_flash = crc; - applyConfig(buffer, size - 2); // Skip CRC + applyConfig(buffer + 1, size - 3); // Skip Type & CRC free(buffer); } From 4d436380ae709b36d0223630ff4e860bd45f71f3 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?J=C3=B6rg=20Ebeling?= Date: Tue, 29 Oct 2024 22:05:02 +0100 Subject: [PATCH 28/32] Optimize hall handling with etl::vector --- Firmware/LowLevel/platformio.ini | 2 +- Firmware/LowLevel/src/datatypes.h | 6 +++ Firmware/LowLevel/src/main.cpp | 63 ++++++++++++------------------- 3 files changed, 32 insertions(+), 39 deletions(-) diff --git a/Firmware/LowLevel/platformio.ini b/Firmware/LowLevel/platformio.ini index 8ba57d49..8cecc9b1 100644 --- a/Firmware/LowLevel/platformio.ini +++ b/Firmware/LowLevel/platformio.ini @@ -28,7 +28,7 @@ lib_deps = bakercp/PacketSerial@^1.4.0 powerbroker2/FireTimer@^1.0.5 https://github.com/ClemensElflein/NeoPixelConnect.git - + etlcpp/Embedded Template Library @ ^20.39.4 debug_tool = custom debug_init_break = diff --git a/Firmware/LowLevel/src/datatypes.h b/Firmware/LowLevel/src/datatypes.h index 9a44a0e9..91781f0b 100644 --- a/Firmware/LowLevel/src/datatypes.h +++ b/Firmware/LowLevel/src/datatypes.h @@ -157,6 +157,12 @@ struct HallConfig { } __attribute__((packed)); #pragma pack(pop) +// For each active hall, we've a handle of it for quick and direct access +struct HallHandle { + HallConfig config; + std::function get_value; +}; + #define MAX_HALL_INPUTS 10 // How much Hall-inputs we support. 4 * OM + 6 * Stock-CoverUI + 0 spare (because not yet required to make it fixed) // LL/HL config packet, bi-directional, flexible-length, with defaults for YF-C500. diff --git a/Firmware/LowLevel/src/main.cpp b/Firmware/LowLevel/src/main.cpp index ee554559..b0be77cb 100644 --- a/Firmware/LowLevel/src/main.cpp +++ b/Firmware/LowLevel/src/main.cpp @@ -20,6 +20,7 @@ #include #include #include +#include #include "datatypes.h" #include "imu.h" @@ -123,8 +124,8 @@ uint16_t ui_interval = 1000; // UI send msg (LED/State) interval ( uint16_t config_crc_in_flash = 0; struct ll_high_level_config llhl_config; // LL/HL configuration (is initialized with YF-C500 defaults) -// Hall input sources, same order as in ll_high_level_config.hall_configs -const std::function halls[MAX_HALL_INPUTS] = { +// Available hall input sources, same order as in ll_high_level_config.hall_configs +const std::function available_halls[MAX_HALL_INPUTS] = { []() { return gpio_get(PIN_EMERGENCY_1); }, // OM-Hall-1 (default Lift1) []() { return gpio_get(PIN_EMERGENCY_2); }, // OM-Hall-2 (default Lift2) []() { return gpio_get(PIN_EMERGENCY_3); }, // OM-Hall-3 (default Stop1) @@ -136,9 +137,8 @@ const std::function halls[MAX_HALL_INPUTS] = { []() { return stock_ui_emergency_state & LL_EMERGENCY_BIT_CU_STOP1; }, // CoverUI-Stop1 []() { return stock_ui_emergency_state & LL_EMERGENCY_BIT_CU_STOP2; }, // CoverUI-Stop2 }; -// Instead of iterating constantly over all halls, we use these compacted ones, whose contain the halls index of the used ones -uint8_t stop_halls[MAX_HALL_INPUTS] = {}; -uint8_t lift_halls[MAX_HALL_INPUTS] = {}; +// Instead of iterating constantly over all available_halls, we use this compacted vector (which only contain the used halls) +etl::vector halls; void sendMessage(void *message, size_t size); void sendUIMessage(void *message, size_t size); @@ -161,33 +161,32 @@ void updateEmergency() { uint8_t last_emergency = status_message.emergency_bitmask & LL_EMERGENCY_BIT_LATCH; uint8_t emergency_state = 0; - // Check all "stop" mode emergency inputs (halls) + // Check all emergency inputs (halls) bool stop_pressed = false; - size_t i; - for (i = 0; i < MAX_HALL_INPUTS; i++) { - if (stop_halls[i] == 0xff) break; // End marker reached - stop_pressed = halls[stop_halls[i]]() ^ llhl_config.hall_configs[stop_halls[i]].active_low; // Get hall value and apply active_low level (invert) - if (stop_pressed) break; // Break at first detected stop + int num_lifted = 0; + for (const auto &hall : halls) { + if (!(hall.get_value() ^ hall.config.active_low)) continue; // Hall isn't triggered + if (hall.config.mode == HallMode::STOP) { + stop_pressed = true; + } else if (hall.config.mode == HallMode::LIFT_TILT) { + num_lifted++; + } + // From logic point of view, it save to escape here if stop_pressed == true AND num_lifted >= 2, but this is very unlikely to happen ever! + // Instead of, we should exit iterating over the remaining halls, if an important emergency case happen, which is STOP got pressed OR >=2 wheels got lifted. + if (stop_pressed || num_lifted >= 2) + break; } // Handle emergency "Stop" buttons if (stop_pressed) { - if (button_emergency_started == 0) button_emergency_started = millis(); // If we just pressed, store the timestamp + if (button_emergency_started == 0) { + button_emergency_started = millis(); // Just pressed, store the timestamp for debouncing + } else if (button_emergency_started > 0 && (millis() - button_emergency_started) >= BUTTON_EMERGENCY_MILLIS) { + emergency_state |= LL_EMERGENCY_BIT_STOP; // Debounced + } } else { button_emergency_started = 0; // Not pressed, reset the time } - if (button_emergency_started > 0 && (millis() - button_emergency_started) >= BUTTON_EMERGENCY_MILLIS) { - emergency_state |= LL_EMERGENCY_BIT_STOP; - } - - // Check all "lifted" mode emergency inputs (halls) - int num_lifted = 0; - for (i = 0; i < MAX_HALL_INPUTS; i++) { - if (lift_halls[i] == 0xff) break; // End marker reached - if (halls[lift_halls[i]]() ^ llhl_config.hall_configs[lift_halls[i]].active_low) // Get hall value and apply active_low level (invert) - num_lifted++; - if (num_lifted >= 2) break; // Break once two wheels are lifted - } // Handle lifted (>=2 wheels are lifted) if (num_lifted >= 2) { @@ -616,22 +615,10 @@ void applyConfig(const uint8_t *buffer, const size_t size) { new_config.hall_configs[i] = rcv_config.hall_configs[i]; } - // Apply active Emergency/Hall configurations to our compacted stop/lift-hall arrays which get used by updateEmergency() - uint8_t stop_hall_idx = 0, lift_hall_idx = 0; + // Apply the new emergency/hall configuration to our compacted stop/lift-hall vector which get used by updateEmergency() for (size_t i = 0; i < MAX_HALL_INPUTS; i++) { - switch (new_config.hall_configs[i].mode) { - case HallMode::LIFT_TILT: - lift_halls[lift_hall_idx] = i; - lift_hall_idx++; - break; - case HallMode::STOP: - stop_halls[stop_hall_idx] = i; - stop_hall_idx++; - break; - } + halls.push_back({new_config.hall_configs[i], available_halls[i]}); } - lift_halls[lift_hall_idx] = 0xff; // End of lift halls marker - stop_halls[stop_hall_idx] = 0xff; // End of stop halls marker llhl_config = new_config; // Make new config live } From e55bc193f762ca22c5771b45d5dfde6472a46e58 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?J=C3=B6rg=20Ebeling?= Date: Tue, 29 Oct 2024 23:29:54 +0100 Subject: [PATCH 29/32] Change ConfigOptions from boolean to tree-state enums --- Firmware/LowLevel/src/datatypes.h | 22 +++++++++++++++++----- Firmware/LowLevel/src/main.cpp | 2 +- 2 files changed, 18 insertions(+), 6 deletions(-) diff --git a/Firmware/LowLevel/src/datatypes.h b/Firmware/LowLevel/src/datatypes.h index 91781f0b..fa76cdba 100644 --- a/Firmware/LowLevel/src/datatypes.h +++ b/Firmware/LowLevel/src/datatypes.h @@ -132,14 +132,26 @@ struct ll_ui_event { } __attribute__((packed)); #pragma pack(pop) +enum class OptionState : unsigned int { + OFF = 0, + ON, + UNDEFINED +}; + #pragma pack(push, 1) struct ConfigOptions { - bool dfp_is_5v : 1; - bool background_sounds : 1; - bool ignore_charging_current : 1; + OptionState dfp_is_5v : 2; + OptionState background_sounds : 2; + OptionState ignore_charging_current : 2; + // Need to block/waster the bits now, to be prepared for future enhancements + OptionState reserved_for_future_use1 : 2; + OptionState reserved_for_future_use2 : 2; + OptionState reserved_for_future_use3 : 2; + OptionState reserved_for_future_use4 : 2; + OptionState reserved_for_future_use5 : 2; } __attribute__((packed)); #pragma pack(pop) -static_assert(sizeof(ConfigOptions) == 1, "Enlarging struct ConfigOption to a sizeof > 1 will break packet compatibilty"); +static_assert(sizeof(ConfigOptions) == 2, "Changing size of ConfigOption != 2 will break packet compatibilty"); typedef char iso639_1[2]; // Two char ISO 639-1 language code @@ -173,7 +185,7 @@ struct ll_high_level_config { // uint8_t type; Just for illustration. Get set in wire buffer with type PACKET_ID_LL_HIGH_LEVEL_CONFIG_REQ or PACKET_ID_LL_HIGH_LEVEL_CONFIG_RSP - ConfigOptions options = {0, 0, 0}; + ConfigOptions options = {.dfp_is_5v = OptionState::OFF, .background_sounds = OptionState::OFF, .ignore_charging_current = OptionState::OFF}; uint16_t rain_threshold = 700; // If (stock CoverUI) rain value < rain_threshold then it rains. Expected to differ between C500, SA and SC types (0xFFFF = unknown) float v_charge_cutoff = 30.0f; // Protective max. charging voltage before charging get switched off (-1 = unknown) float i_charge_cutoff = 1.5f; // Protective max. charging current before charging get switched off (-1 = unknown) diff --git a/Firmware/LowLevel/src/main.cpp b/Firmware/LowLevel/src/main.cpp index b0be77cb..e2dc8518 100644 --- a/Firmware/LowLevel/src/main.cpp +++ b/Firmware/LowLevel/src/main.cpp @@ -752,7 +752,7 @@ void loop() { (float) analogRead(PIN_ANALOG_BATTERY_VOLTAGE) * (3.3f / 4096.0f) * ((VIN_R1 + VIN_R2) / VIN_R2); status_message.v_charge = (float) analogRead(PIN_ANALOG_CHARGE_VOLTAGE) * (3.3f / 4096.0f) * ((VIN_R1 + VIN_R2) / VIN_R2); - status_message.charging_current = llhl_config.options.ignore_charging_current ? -1.0f : (float)analogRead(PIN_ANALOG_CHARGE_CURRENT) * (3.3f / 4096.0f) / (CURRENT_SENSE_GAIN * R_SHUNT); + status_message.charging_current = llhl_config.options.ignore_charging_current == OptionState::ON ? -1.0f : (float)analogRead(PIN_ANALOG_CHARGE_CURRENT) * (3.3f / 4096.0f) / (CURRENT_SENSE_GAIN * R_SHUNT); status_message.status_bitmask = (status_message.status_bitmask & 0b11111011) | ((charging_allowed & 0b1) << 2); status_message.status_bitmask = (status_message.status_bitmask & 0b11011111) | ((sound_available & 0b1) << 5); From 480cadf2f1701829be64ac8f3afd055a93dcc48a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?J=C3=B6rg=20Ebeling?= Date: Tue, 29 Oct 2024 23:33:56 +0100 Subject: [PATCH 30/32] Change shutdown_esc_max_pitch to uint8_t --- Firmware/LowLevel/src/datatypes.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Firmware/LowLevel/src/datatypes.h b/Firmware/LowLevel/src/datatypes.h index fa76cdba..bba80b49 100644 --- a/Firmware/LowLevel/src/datatypes.h +++ b/Firmware/LowLevel/src/datatypes.h @@ -194,7 +194,7 @@ struct ll_high_level_config { float v_battery_full = 28.7f - 0.3f; // Full battery voltage used for % calc of capacity (-1 = unknown) uint16_t lift_period = 100; // Period (ms) for >=2 wheels to be lifted in order to count as emergency (0 = disable, 0xFFFF = unknown). This is to filter uneven ground uint16_t tilt_period = 2500; // Period (ms) for a single wheel to be lifted in order to count as emergency (0 = disable, 0xFFFF = unknown). This is to filter uneven ground - float shutdown_esc_max_pitch = 0.0f; // Do not shutdown ESCs if absolute pitch angle is greater than this (0 = disable, 0xffff = unknown) (to be implemented) + uint8_t shutdown_esc_max_pitch = 0; // Do not shutdown ESCs if absolute pitch angle is greater than this (0 = disable, 0xffff = unknown) (to be implemented, see PR #97) iso639_1 language = {'e', 'n'}; // ISO 639-1 (2-char) language code (en, de, ...) uint8_t volume = 80; // Volume (0-100%) feedback (if directly changed i.e. via CoverUI or WebApp) (0xff = do not change) HallConfig hall_configs[MAX_HALL_INPUTS] = { From d18509091f492be50faffe07a3356e2007242414 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?J=C3=B6rg=20Ebeling?= Date: Tue, 29 Oct 2024 23:54:31 +0100 Subject: [PATCH 31/32] Add new/missing config values to applyConfig() --- Firmware/LowLevel/src/main.cpp | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/Firmware/LowLevel/src/main.cpp b/Firmware/LowLevel/src/main.cpp index e2dc8518..527f40ce 100644 --- a/Firmware/LowLevel/src/main.cpp +++ b/Firmware/LowLevel/src/main.cpp @@ -594,11 +594,13 @@ void applyConfig(const uint8_t *buffer, const size_t size) { // Take over of payload values. This could also be made the other way around, which would save the copy of the "leading" // values, but I felt it's more secure to do it this way (in special for further packet enlargements) - // HL always force these member - new_config.options = rcv_config.options; + // HL always force language strncpy(new_config.language, rcv_config.language, 2); // Take over only those (HL) values which are not "undefined/unknown" + if (rcv_config.options.dfp_is_5v != OptionState::UNDEFINED) new_config.options.dfp_is_5v = rcv_config.options.dfp_is_5v; + if (rcv_config.options.background_sounds != OptionState::UNDEFINED) new_config.options.background_sounds = rcv_config.options.background_sounds; + if (rcv_config.options.ignore_charging_current != OptionState::UNDEFINED) new_config.options.ignore_charging_current = rcv_config.options.ignore_charging_current; if (rcv_config.rain_threshold != 0xffff) new_config.rain_threshold = rcv_config.rain_threshold; if (rcv_config.v_charge_cutoff >= 0) new_config.v_charge_cutoff = min(rcv_config.v_charge_cutoff, 36.0f); // Rated max. limited by MAX20405 if (rcv_config.i_charge_cutoff >= 0) new_config.i_charge_cutoff = min(rcv_config.i_charge_cutoff, 5.0f); // Absolute max. limited by D2/D3 Schottky @@ -607,6 +609,7 @@ void applyConfig(const uint8_t *buffer, const size_t size) { if (rcv_config.v_battery_full >= 0) new_config.v_battery_full = rcv_config.v_battery_full; if (rcv_config.lift_period != 0xffff) new_config.lift_period = rcv_config.lift_period; if (rcv_config.tilt_period != 0xffff) new_config.tilt_period = rcv_config.tilt_period; + if (rcv_config.shutdown_esc_max_pitch != 0xff) new_config.shutdown_esc_max_pitch = rcv_config.shutdown_esc_max_pitch; if (rcv_config.volume != 0xff) new_config.volume = rcv_config.volume; // Take over those hall inputs which are not undefined From 542419f9f29e3c877669d7d69ee2942f2385cb99 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?J=C3=B6rg=20Ebeling?= Date: Wed, 30 Oct 2024 17:01:54 +0100 Subject: [PATCH 32/32] Fix hall handling --- Firmware/LowLevel/src/main.cpp | 33 ++++++++++++++++----------------- 1 file changed, 16 insertions(+), 17 deletions(-) diff --git a/Firmware/LowLevel/src/main.cpp b/Firmware/LowLevel/src/main.cpp index 527f40ce..4b8d61ac 100644 --- a/Firmware/LowLevel/src/main.cpp +++ b/Firmware/LowLevel/src/main.cpp @@ -165,16 +165,16 @@ void updateEmergency() { bool stop_pressed = false; int num_lifted = 0; for (const auto &hall : halls) { - if (!(hall.get_value() ^ hall.config.active_low)) continue; // Hall isn't triggered - if (hall.config.mode == HallMode::STOP) { - stop_pressed = true; - } else if (hall.config.mode == HallMode::LIFT_TILT) { - num_lifted++; + if (hall.get_value() ^ hall.config.active_low) { // Get emergency input value and invert if low-active + if (hall.config.mode == HallMode::STOP) { + stop_pressed = true; + } else if (hall.config.mode == HallMode::LIFT_TILT) { + num_lifted++; + } + // Unlikely to happen, but there's no more emergency than stop and multiple-wheels lifted + if (stop_pressed && num_lifted >= 2) + break; } - // From logic point of view, it save to escape here if stop_pressed == true AND num_lifted >= 2, but this is very unlikely to happen ever! - // Instead of, we should exit iterating over the remaining halls, if an important emergency case happen, which is STOP got pressed OR >=2 wheels got lifted. - if (stop_pressed || num_lifted >= 2) - break; } // Handle emergency "Stop" buttons @@ -591,9 +591,6 @@ void applyConfig(const uint8_t *buffer, const size_t size) { // because we need to ensure that re-commented mower_config parameter get the LL-default value and not the last saved one! ll_high_level_config new_config; - // Take over of payload values. This could also be made the other way around, which would save the copy of the "leading" - // values, but I felt it's more secure to do it this way (in special for further packet enlargements) - // HL always force language strncpy(new_config.language, rcv_config.language, 2); @@ -612,17 +609,19 @@ void applyConfig(const uint8_t *buffer, const size_t size) { if (rcv_config.shutdown_esc_max_pitch != 0xff) new_config.shutdown_esc_max_pitch = rcv_config.shutdown_esc_max_pitch; if (rcv_config.volume != 0xff) new_config.volume = rcv_config.volume; - // Take over those hall inputs which are not undefined + // Handle all emergency/halls + halls.clear(); for (size_t i = 0; i < MAX_HALL_INPUTS; i++) { + // Take over those halls which are not "undefined" if (rcv_config.hall_configs[i].mode != HallMode::UNDEFINED) new_config.hall_configs[i] = rcv_config.hall_configs[i]; - } - // Apply the new emergency/hall configuration to our compacted stop/lift-hall vector which get used by updateEmergency() - for (size_t i = 0; i < MAX_HALL_INPUTS; i++) { + if (new_config.hall_configs[i].mode == HallMode::OFF) + continue; + + // Apply used hall to our compacted stop/lift-hall vector which get used by updateEmergency() halls.push_back({new_config.hall_configs[i], available_halls[i]}); } - llhl_config = new_config; // Make new config live }