Skip to content

Commit

Permalink
Enlargable Config Packet (#163)
Browse files Browse the repository at this point in the history
In relation to ClemensElflein/OpenMower#110

Roadmap:

- [x] Decide for config protocol and struct
- [x] LowLevel (OpenMower Pico-FW) please see
ClemensElflein/OpenMower#110
- [x] HighLevel (open_mower_ros)
  - [x] Implement packet handling
  - [x] Implement config value handling
    - [x] Charge & Battery
    - [x] Hall sensor inputs
    - [x] Emergency
    - [x] Misc
- [x] Test with old LL-FW

<sub>:hammer: = Currently working on</sub>

---------

Co-authored-by: Clemens Elflein <[email protected]>
  • Loading branch information
Apehaenger and ClemensElflein authored Nov 15, 2024
1 parent ac81497 commit 06c35c4
Show file tree
Hide file tree
Showing 8 changed files with 421 additions and 79 deletions.
53 changes: 53 additions & 0 deletions config/mower_config.schema.json
Original file line number Diff line number Diff line change
Expand Up @@ -58,6 +58,13 @@
"default": "xbox360",
"description": "Select your gamepad. The cheap ones are usually xbox360.",
"x-environment-variable": "OM_MOWER_GAMEPAD"
},
"OM_IGNORE_CHARGING_CURRENT": {
"type": "boolean",
"default": false,
"title": "Ignore Charging Current",
"description": "Set to True if you're affected by a wrong IC2 sourcing. Read here https://openmower.de/docs/versions/errata/ic2-is-wrong/ for more details",
"x-environment-variable": "OM_IGNORE_CHARGING_CURRENT"
}
}
},
Expand Down Expand Up @@ -506,6 +513,52 @@
"type": "number",
"description": "Use perimeter sensor for docking. Set to 1 or 2 depending on the signal selected on the docking station. This is only supported by Mowgli builds for now.",
"x-environment-variable": "OM_PERIMETER_SIGNAL"
},
"OM_EMERGENCY_INPUT_CONFIG": {
"type": "string",
"default": "",
"description": "Comma separated list of emergency inputs (halls or stop), where each sensor can be configured in one of the following modes '[!]<I>gnore|<U>nused|<S>top|<L>Lift'",
"x-environment-variable": "OM_EMERGENCY_INPUT_CONFIG"
},
"OM_EMERGENCY_LIFT_PERIOD": {
"type": "number",
"default": -1,
"description": "Period (ms) for >=2 wheels to be lifted in order to count as emergency (0 = disable)",
"x-environment-variable": "OM_EMERGENCY_LIFT_PERIOD"
},
"OM_EMERGENCY_TILT_PERIOD": {
"type": "number",
"default": -1,
"description": "Period (ms) for a single wheel to be lifted in order to count as emergency (0 = disable)",
"x-environment-variable": "OM_EMERGENCY_TILT_PERIOD"
},
"OM_CU_RAIN_THRESHOLD": {
"type": "number",
"default": -1,
"title": "Stock-CoverUI rain sensor threshold",
"description": "Stock-CoverUI limited rain sensor threshold, below which humidity/dryness value get identified as rain. As higher, as more dry. Default to 700",
"x-environment-variable": "OM_CU_RAIN_THRESHOLD"
},
"OM_BATTERY_CRITICAL_HIGH_VOLTAGE": {
"type": "number",
"default": -1,
"title": "Max. battery voltage",
"description": "Max. battery voltage before charging get switched off",
"x-environment-variable": "OM_BATTERY_CRITICAL_HIGH_VOLTAGE"
},
"OM_CHARGE_CRITICAL_HIGH_VOLTAGE": {
"type": "number",
"default": -1,
"title": "Max. charge voltage",
"description": "Max. charge voltage before charging get switched off",
"x-environment-variable": "OM_CHARGE_CRITICAL_HIGH_VOLTAGE"
},
"OM_CHARGE_CRITICAL_HIGH_CURRENT": {
"type": "number",
"default": -1,
"title": "Max. charge current",
"description": "Max. charge current before charging get switched off",
"x-environment-variable": "OM_CHARGE_CRITICAL_HIGH_CURRENT"
}
}
}
Expand Down
56 changes: 56 additions & 0 deletions config/mower_config.sh.example
Original file line number Diff line number Diff line change
Expand Up @@ -64,6 +64,11 @@ export OM_MOWER_GAMEPAD="xbox360"
# Output will be stored in your $HOME
# export OM_ENABLE_RECORDING_ALL=False

# Ignore Charging Current
# If you're affected by a wrong IC2 sourcing, read here https://openmower.de/docs/versions/errata/ic2-is-wrong/
# for more details, you can disable the wrong charging current reading by disabling the charging protection via:
#export OM_IGNORE_CHARGING_CURRENT=True

# Full Sound Support - But read on carefully:
# Up to (and inclusive) OM hardware version 0.13.x, DFPlayer's power supply is set by default to 3.3V.
# This is done by solder jumper "JP1" whose board track is by default at 3.3V.
Expand Down Expand Up @@ -196,6 +201,14 @@ export OM_BATTERY_EMPTY_VOLTAGE=24.0
# Immediate dock if voltage is critical
export OM_BATTERY_CRITICAL_VOLTAGE=23.0

# Absolute battery and charging limits, before charging get switched off
# Over-voltage battery protection
#export OM_BATTERY_CRITICAL_HIGH_VOLTAGE=29.0
# Over-voltage charge protection
#export OM_CHARGE_CRITICAL_HIGH_VOLTAGE=30.0
# Over-current charge protection
#export OM_CHARGE_CRITICAL_HIGH_CURRENT=1.5

# Mower motor temperatures to stop and start mowing
export OM_MOWING_MOTOR_TEMP_HIGH=80.0
export OM_MOWING_MOTOR_TEMP_LOW=40.0
Expand Down Expand Up @@ -226,6 +239,49 @@ export OM_RAIN_MODE=0
# How long to wait after rain to resume mowing when mode is "Dock Until Dry"
export OM_RAIN_DELAY_MINUTES=30

# Rain threshold (Stock-CoverUI limited parameter)
# A rain sensor threshold, below which humidity/dryness value get identified as rain.
# As higher, as more dry, defaults to 700.
#export OM_CU_RAIN_THRESHOLD=700

# Hall / Emergency input configuration
#
# This is an expert configuration option, use it only for custom builds!
# The normal YardForce Classic 500 user should leave all options in commented state.
#
# We do have 10 emergency inputs. 4 * OM-Hall1 up to OM-Hall4, plus 6 * Stock-CoverUI.
#
# Each emergency input can be configure in one of the following modes:
# I = Ignore this input. Use this mode for inputs which aren't connected to any sensor, or if you wish that this sensor get ignored
# U = Undefined (don't touch this input, leave it as it's by default)
# S = Stop. This input shall be used as "Stop" button input
# L = Lift. Use for an input with lift and tilt support like for wheel sensors
#
# In addition, each mode letter, can be prefixed with a "!" character, which indicate that this sensor shall be handled as "low-active" sensor
#
# All sensors which shall be configured, have to be placed in a comma separated list in the following order:
# OM-Hall1, OM-Hall2, OM-Hall3, OM-Hall4
# If you've a FW-Moded Stock-CoverUI up to CoverUI FW 2.0x, with attached sensors/buttons, you can append the list with the following inputs:
# CoverUI-LIFT|LIFTX, Ignore, CoverUI-LBUMP|RBUMP, Ignore, CoverUI-Stop1, CoverUI-Stop2
# For those with a CoverUI FW as of 2.1x the appendable list of inputs is:
# CoverUI-LIFT, CoverUI-LIFTX, CoverUI-LBUMP, CoverUI-RBUMP, CoverUI-Stop1, CoverUI-Stop2
#
# Here's an example of a standard Classic 500 configuration where the sensors got attached as documented,
# which is Hall1+2 to the front wheel-lift sensors, and Hall3+4 to the top cover stop-button halls:
# export OM_EMERGENCY_INPUT_CONFIG="!L, !L, !S, !S"
# Yes, "!x" (low-active), because Classic 500 models, pull the input to low when they get triggered (whereas all CoverUI signals are "high-active")
#
#export OM_EMERGENCY_INPUT_CONFIG=""
#
# Lift period, to filter uneven ground
# Period (ms) for >=2 wheels to be lifted in order to count as emergency (0 = disable)
#export OM_EMERGENCY_LIFT_PERIOD="100"
#
# Tilt period, to filter uneven ground
# Period (ms) for a single wheel to be lifted in order to count as emergency (0 = disable)
#export OM_EMERGENCY_TILT_PERIOD="2500"


################################
## External MQTT Broker ##
################################
Expand Down
1 change: 1 addition & 0 deletions src/mower_comms/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@ project(mower_comms)
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
find_package(catkin REQUIRED COMPONENTS
dynamic_reconfigure
mower_msgs
sensor_msgs
roscpp
Expand Down
86 changes: 67 additions & 19 deletions src/mower_comms/src/ll_datatypes.h
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,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

Expand All @@ -47,10 +47,8 @@ struct ll_status {
float uss_ranges_m[5];
// Emergency bitmask:
// Bit 0: Emergency latch
// Bit 1: Emergency 0 active
// Bit 2: Emergency 1 active
// Bit 3: Emergency 2 active
// Bit 4: Emergency 3 active
// Bit 1: Emergency/Lift (or tilt)
// Bit 2: Emergency/Stop
uint8_t emergency_bitmask;
// Charge voltage
float v_charge;
Expand Down Expand Up @@ -111,24 +109,74 @@ struct ll_high_level_state {
} __attribute__((packed));
#pragma pack(pop)

#define LL_HIGH_LEVEL_CONFIG_MAX_COMMS_VERSION 1 // Max. comms packet version supported by this open_mower_ros
#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
enum class OptionState : unsigned int {
OFF = 0,
ON,
UNDEFINED
};

#pragma pack(push, 1)
struct ConfigOptions {
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) == 2, "Changing size of ConfigOption != 2 will break packet compatibilty");

typedef char iso639_1[2]; // Two char ISO 639-1 language code

enum class HallMode : unsigned int {
OFF = 0,
LIFT_TILT, // Wheel lifted and wheels tilted functionality
STOP, // Stop mower
UNDEFINED // This is used by foreign side to inform that it doesn't has a configuration for this sensor
};

#pragma pack(push, 1)
struct HallConfig {
HallConfig(HallMode t_mode = HallMode::UNDEFINED, bool t_active_low = false)
: mode(t_mode), active_low(t_active_low) {};

HallMode mode : 3; // 1 bit reserved
bool active_low : 1;
} __attribute__((packed));
#pragma pack(pop)

#define MAX_HALL_INPUTS 10 // How much Hall-inputs we do support. 4 * OM + 6 * Stock-CoverUI

// LL/HL config packet, bi-directional, flexible-length
#pragma pack(push, 1)
struct ll_high_level_config {
uint8_t type = PACKET_ID_LL_HIGH_LEVEL_CONFIG_RSP; // By default, respond only (for now)
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). -1 = don't change
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 later in wire buffer with type PACKET_ID_LL_HIGH_LEVEL_CONFIG_*

// clang-format off
ConfigOptions options = {.dfp_is_5v = OptionState::OFF, .background_sounds = OptionState::OFF, .ignore_charging_current = OptionState::OFF};
uint16_t rain_threshold = 0xffff; // If (stock CoverUI) rain value < rain_threshold then it rains
float v_charge_cutoff = -1; // Protective max. charging voltage before charging get switched off (-1 = unknown)
float i_charge_cutoff = -1; // Protective max. charging current before charging get switched off (-1 = unknown)
float v_battery_cutoff = -1; // Protective max. battery voltage before charging get switched off (-1 = unknown)
float v_battery_empty = -1; // Empty battery voltage used for % calc of capacity (-1 = unknown)
float v_battery_full = -1; // Full battery voltage used for % calc of capacity (-1 = unknown)
uint16_t lift_period = 0xffff; // Period (ms) for >=2 wheels to be lifted in order to count as emergency (0 = disable, 0xFFFF = unknown)
uint16_t tilt_period = 0xffff; // Period (ms) for a single wheel to be lifted in order to count as emergency (0 = disable, 0xFFFF = unknown)
uint8_t shutdown_esc_max_pitch = 0xff; // Do not shutdown ESCs if absolute pitch angle is greater than this (0 = disable, 0xff = unknown) (to be implemented, see OpenMower PR #97)
iso639_1 language = {'e', 'n'}; // ISO 639-1 (2-char) language code (en, de, ...)
uint8_t volume = 0xff; // Volume (0-100%) feedback (if directly changed i.e. via CoverUI) (0xff = do not change)
HallConfig hall_configs[MAX_HALL_INPUTS]; // Set all to UNDEFINED
// 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 later within the wire buffer
// clang-format on
} __attribute__((packed));
#pragma pack(pop)

Expand Down
Loading

0 comments on commit 06c35c4

Please sign in to comment.