Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Enlargeable Config Packet #110

Merged
Merged
Show file tree
Hide file tree
Changes from 11 commits
Commits
Show all changes
33 commits
Select commit Hold shift + click to select a range
6d00ee3
Initial proposal
Apehaenger Oct 7, 2024
e19c952
Add missing files
Apehaenger Oct 7, 2024
f3936e6
Abort one large config struct consideration
Apehaenger Oct 9, 2024
d90b6ca
Finish flexible length config packet
Apehaenger Oct 10, 2024
9a50a05
Cleanup, add and rename config struct member
Apehaenger Oct 11, 2024
13aff7f
refactor: create applyConfig()
rovo89 Oct 11, 2024
1c0cfac
PoC for LittleFS
rovo89 Oct 11, 2024
68ed301
Implement review hints of rovo89
Apehaenger Oct 11, 2024
1ff7d31
Don't write config to flash if it hasn't changed
rovo89 Oct 11, 2024
bca5826
Implement review hints of rovo89
Apehaenger Oct 11, 2024
7899164
Merge pull request #1 from rovo89/config_flash
Apehaenger Oct 12, 2024
4f11010
Minor LittleFS implementation changes
Apehaenger Oct 12, 2024
0075f68
Intermediate result after protocol implementation with ROS
Apehaenger Oct 14, 2024
37f2ac6
Missing commit
Apehaenger Oct 14, 2024
9e24b05
Intermediate commit #2
Apehaenger Oct 18, 2024
7eaa6fd
Adjust v_charge_cutoff to MAX20405
Apehaenger Oct 18, 2024
5f5d5b8
Change config_bitmask to option bitfield
Apehaenger Oct 20, 2024
a1a6492
Make IGNORE_CHARGING_CURRENT configurable via LL/HL config `options.i…
Apehaenger Oct 20, 2024
5b18e4a
Finalize LittleFS
Apehaenger Oct 20, 2024
859de1b
Finish new flexible hall implementation
Apehaenger Oct 22, 2024
4135fa5
Remove IGNORE_CHARGING_CURRENT builds from artifacts
Apehaenger Oct 22, 2024
fe8e829
Make halls const
Apehaenger Oct 22, 2024
32d6576
Apply received packet on default-config (instead of live-config)
Apehaenger Oct 24, 2024
2328792
Add configurable (Stock-CoverUI) rain threshold
Apehaenger Oct 24, 2024
21e5baf
Change config packet IDs
Apehaenger Oct 26, 2024
12874d2
Cleanup
Apehaenger Oct 26, 2024
485e0a8
Cosmetic changes
Apehaenger Oct 28, 2024
7ba963d
Store config packet instead of effective config
Apehaenger Oct 28, 2024
4d43638
Optimize hall handling with etl::vector
Apehaenger Oct 29, 2024
e55bc19
Change ConfigOptions from boolean to tree-state enums
Apehaenger Oct 29, 2024
480cadf
Change shutdown_esc_max_pitch to uint8_t
Apehaenger Oct 29, 2024
d185090
Add new/missing config values to applyConfig()
Apehaenger Oct 29, 2024
542419f
Fix hall handling
Apehaenger Oct 30, 2024
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
26 changes: 26 additions & 0 deletions Firmware/LowLevel/include/config_defaults.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
#ifndef _CONFIG_H
Apehaenger marked this conversation as resolved.
Show resolved Hide resolved
#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
Apehaenger marked this conversation as resolved.
Show resolved Hide resolved

#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
42 changes: 42 additions & 0 deletions Firmware/LowLevel/include/debug.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,42 @@
// 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) \
Apehaenger marked this conversation as resolved.
Show resolved Hide resolved
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_
1 change: 1 addition & 0 deletions Firmware/LowLevel/platformio.ini
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
64 changes: 53 additions & 11 deletions Firmware/LowLevel/src/datatypes.h
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
#define _DATATYPES_H

#include <stdint.h>
#include "config_defaults.h"

#define PACKET_ID_LL_STATUS 1
#define PACKET_ID_LL_IMU 2
Expand Down Expand Up @@ -60,7 +61,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
Expand All @@ -74,6 +75,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;
Expand Down Expand Up @@ -135,22 +137,62 @@ 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_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

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)
};

// FIXME: Decide later which is more comfortable, activeLow = 0 | 1
Apehaenger marked this conversation as resolved.
Show resolved Hide resolved
enum class HallLevel : uint8_t {
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;
HallLevel level : 1;
} __attribute__((packed));
#pragma pack(pop)

#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.
#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;
// 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 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)
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::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

// uint16_t crc; Just for illustration, that it get appended, but only within the wire buffer
} __attribute__((packed));
#pragma pack(pop)

Expand Down
120 changes: 88 additions & 32 deletions Firmware/LowLevel/src/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,9 +19,12 @@
#include <FastCRC.h>
#include <PacketSerial.h>
#include "datatypes.h"
#include "config_defaults.h"
#include "pins.h"
#include "ui_board.h"
#include "imu.h"
#include "debug.h"
#include <LittleFS.h>

#ifdef ENABLE_SOUND_MODULE
#include <soundsystem.h>
Expand All @@ -32,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
Expand Down Expand Up @@ -62,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

Expand Down Expand Up @@ -123,15 +118,17 @@ 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 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_*
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);
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
Expand Down Expand Up @@ -372,9 +369,7 @@ void setup() {
// Therefore, we pause the other core until setup() was a success
rp2040.idleOtherCore();

#ifdef USB_DEBUG
DEBUG_SERIAL.begin(9600);
#endif
DEBUG_BEGIN(9600);
Apehaenger marked this conversation as resolved.
Show resolved Hide resolved

emergency_latch = true;
ROS_running = false;
Expand Down Expand Up @@ -424,6 +419,10 @@ void setup() {
UISerial.setStream(&UI1_SERIAL);
UISerial.setPacketHandler(&onUIPacketReceived);

// Initialize flash and try to read config
LittleFS.begin();
readConfigFromFlash();

/*
* IMU INITIALIZATION
*/
Expand Down Expand Up @@ -548,12 +547,37 @@ 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;
Apehaenger marked this conversation as resolved.
Show resolved Hide resolved
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 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
Apehaenger marked this conversation as resolved.
Show resolved Hide resolved

// 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) {
Expand Down Expand Up @@ -590,17 +614,11 @@ 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))
{
// 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
} 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();
Apehaenger marked this conversation as resolved.
Show resolved Hide resolved

if (buffer[0] == PACKET_ID_LL_HIGH_LEVEL_CONFIG_REQ)
sendConfigMessage(PACKET_ID_LL_HIGH_LEVEL_CONFIG_RSP);
Expand All @@ -609,7 +627,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 < 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() {
Expand Down Expand Up @@ -790,3 +808,41 @@ 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");
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;

config_crc_in_flash = crc;
applyConfig(buffer, size);
free(buffer);
}
Loading