Skip to content

Commit 06c35c4

Browse files
Enlargable Config Packet (#163)
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]>
1 parent ac81497 commit 06c35c4

File tree

8 files changed

+421
-79
lines changed

8 files changed

+421
-79
lines changed

config/mower_config.schema.json

Lines changed: 53 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -58,6 +58,13 @@
5858
"default": "xbox360",
5959
"description": "Select your gamepad. The cheap ones are usually xbox360.",
6060
"x-environment-variable": "OM_MOWER_GAMEPAD"
61+
},
62+
"OM_IGNORE_CHARGING_CURRENT": {
63+
"type": "boolean",
64+
"default": false,
65+
"title": "Ignore Charging Current",
66+
"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",
67+
"x-environment-variable": "OM_IGNORE_CHARGING_CURRENT"
6168
}
6269
}
6370
},
@@ -506,6 +513,52 @@
506513
"type": "number",
507514
"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.",
508515
"x-environment-variable": "OM_PERIMETER_SIGNAL"
516+
},
517+
"OM_EMERGENCY_INPUT_CONFIG": {
518+
"type": "string",
519+
"default": "",
520+
"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'",
521+
"x-environment-variable": "OM_EMERGENCY_INPUT_CONFIG"
522+
},
523+
"OM_EMERGENCY_LIFT_PERIOD": {
524+
"type": "number",
525+
"default": -1,
526+
"description": "Period (ms) for >=2 wheels to be lifted in order to count as emergency (0 = disable)",
527+
"x-environment-variable": "OM_EMERGENCY_LIFT_PERIOD"
528+
},
529+
"OM_EMERGENCY_TILT_PERIOD": {
530+
"type": "number",
531+
"default": -1,
532+
"description": "Period (ms) for a single wheel to be lifted in order to count as emergency (0 = disable)",
533+
"x-environment-variable": "OM_EMERGENCY_TILT_PERIOD"
534+
},
535+
"OM_CU_RAIN_THRESHOLD": {
536+
"type": "number",
537+
"default": -1,
538+
"title": "Stock-CoverUI rain sensor threshold",
539+
"description": "Stock-CoverUI limited rain sensor threshold, below which humidity/dryness value get identified as rain. As higher, as more dry. Default to 700",
540+
"x-environment-variable": "OM_CU_RAIN_THRESHOLD"
541+
},
542+
"OM_BATTERY_CRITICAL_HIGH_VOLTAGE": {
543+
"type": "number",
544+
"default": -1,
545+
"title": "Max. battery voltage",
546+
"description": "Max. battery voltage before charging get switched off",
547+
"x-environment-variable": "OM_BATTERY_CRITICAL_HIGH_VOLTAGE"
548+
},
549+
"OM_CHARGE_CRITICAL_HIGH_VOLTAGE": {
550+
"type": "number",
551+
"default": -1,
552+
"title": "Max. charge voltage",
553+
"description": "Max. charge voltage before charging get switched off",
554+
"x-environment-variable": "OM_CHARGE_CRITICAL_HIGH_VOLTAGE"
555+
},
556+
"OM_CHARGE_CRITICAL_HIGH_CURRENT": {
557+
"type": "number",
558+
"default": -1,
559+
"title": "Max. charge current",
560+
"description": "Max. charge current before charging get switched off",
561+
"x-environment-variable": "OM_CHARGE_CRITICAL_HIGH_CURRENT"
509562
}
510563
}
511564
}

config/mower_config.sh.example

Lines changed: 56 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -64,6 +64,11 @@ export OM_MOWER_GAMEPAD="xbox360"
6464
# Output will be stored in your $HOME
6565
# export OM_ENABLE_RECORDING_ALL=False
6666

67+
# Ignore Charging Current
68+
# If you're affected by a wrong IC2 sourcing, read here https://openmower.de/docs/versions/errata/ic2-is-wrong/
69+
# for more details, you can disable the wrong charging current reading by disabling the charging protection via:
70+
#export OM_IGNORE_CHARGING_CURRENT=True
71+
6772
# Full Sound Support - But read on carefully:
6873
# Up to (and inclusive) OM hardware version 0.13.x, DFPlayer's power supply is set by default to 3.3V.
6974
# This is done by solder jumper "JP1" whose board track is by default at 3.3V.
@@ -196,6 +201,14 @@ export OM_BATTERY_EMPTY_VOLTAGE=24.0
196201
# Immediate dock if voltage is critical
197202
export OM_BATTERY_CRITICAL_VOLTAGE=23.0
198203

204+
# Absolute battery and charging limits, before charging get switched off
205+
# Over-voltage battery protection
206+
#export OM_BATTERY_CRITICAL_HIGH_VOLTAGE=29.0
207+
# Over-voltage charge protection
208+
#export OM_CHARGE_CRITICAL_HIGH_VOLTAGE=30.0
209+
# Over-current charge protection
210+
#export OM_CHARGE_CRITICAL_HIGH_CURRENT=1.5
211+
199212
# Mower motor temperatures to stop and start mowing
200213
export OM_MOWING_MOTOR_TEMP_HIGH=80.0
201214
export OM_MOWING_MOTOR_TEMP_LOW=40.0
@@ -226,6 +239,49 @@ export OM_RAIN_MODE=0
226239
# How long to wait after rain to resume mowing when mode is "Dock Until Dry"
227240
export OM_RAIN_DELAY_MINUTES=30
228241

242+
# Rain threshold (Stock-CoverUI limited parameter)
243+
# A rain sensor threshold, below which humidity/dryness value get identified as rain.
244+
# As higher, as more dry, defaults to 700.
245+
#export OM_CU_RAIN_THRESHOLD=700
246+
247+
# Hall / Emergency input configuration
248+
#
249+
# This is an expert configuration option, use it only for custom builds!
250+
# The normal YardForce Classic 500 user should leave all options in commented state.
251+
#
252+
# We do have 10 emergency inputs. 4 * OM-Hall1 up to OM-Hall4, plus 6 * Stock-CoverUI.
253+
#
254+
# Each emergency input can be configure in one of the following modes:
255+
# 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
256+
# U = Undefined (don't touch this input, leave it as it's by default)
257+
# S = Stop. This input shall be used as "Stop" button input
258+
# L = Lift. Use for an input with lift and tilt support like for wheel sensors
259+
#
260+
# In addition, each mode letter, can be prefixed with a "!" character, which indicate that this sensor shall be handled as "low-active" sensor
261+
#
262+
# All sensors which shall be configured, have to be placed in a comma separated list in the following order:
263+
# OM-Hall1, OM-Hall2, OM-Hall3, OM-Hall4
264+
# 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:
265+
# CoverUI-LIFT|LIFTX, Ignore, CoverUI-LBUMP|RBUMP, Ignore, CoverUI-Stop1, CoverUI-Stop2
266+
# For those with a CoverUI FW as of 2.1x the appendable list of inputs is:
267+
# CoverUI-LIFT, CoverUI-LIFTX, CoverUI-LBUMP, CoverUI-RBUMP, CoverUI-Stop1, CoverUI-Stop2
268+
#
269+
# Here's an example of a standard Classic 500 configuration where the sensors got attached as documented,
270+
# which is Hall1+2 to the front wheel-lift sensors, and Hall3+4 to the top cover stop-button halls:
271+
# export OM_EMERGENCY_INPUT_CONFIG="!L, !L, !S, !S"
272+
# Yes, "!x" (low-active), because Classic 500 models, pull the input to low when they get triggered (whereas all CoverUI signals are "high-active")
273+
#
274+
#export OM_EMERGENCY_INPUT_CONFIG=""
275+
#
276+
# Lift period, to filter uneven ground
277+
# Period (ms) for >=2 wheels to be lifted in order to count as emergency (0 = disable)
278+
#export OM_EMERGENCY_LIFT_PERIOD="100"
279+
#
280+
# Tilt period, to filter uneven ground
281+
# Period (ms) for a single wheel to be lifted in order to count as emergency (0 = disable)
282+
#export OM_EMERGENCY_TILT_PERIOD="2500"
283+
284+
229285
################################
230286
## External MQTT Broker ##
231287
################################

src/mower_comms/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -8,6 +8,7 @@ project(mower_comms)
88
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
99
## is used, also find other catkin packages
1010
find_package(catkin REQUIRED COMPONENTS
11+
dynamic_reconfigure
1112
mower_msgs
1213
sensor_msgs
1314
roscpp

src/mower_comms/src/ll_datatypes.h

Lines changed: 67 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -24,8 +24,8 @@
2424
#define PACKET_ID_LL_STATUS 1
2525
#define PACKET_ID_LL_IMU 2
2626
#define PACKET_ID_LL_UI_EVENT 3
27-
#define PACKET_ID_LL_HIGH_LEVEL_CONFIG_REQ 0x21 // ll_high_level_config and request config from receiver
28-
#define PACKET_ID_LL_HIGH_LEVEL_CONFIG_RSP 0x22 // ll_high_level_config response
27+
#define PACKET_ID_LL_HIGH_LEVEL_CONFIG_REQ 0x11 // ll_high_level_config and request config from receiver
28+
#define PACKET_ID_LL_HIGH_LEVEL_CONFIG_RSP 0x12 // ll_high_level_config response
2929
#define PACKET_ID_LL_HEARTBEAT 0x42
3030
#define PACKET_ID_LL_HIGH_LEVEL_STATE 0x43
3131

@@ -47,10 +47,8 @@ struct ll_status {
4747
float uss_ranges_m[5];
4848
// Emergency bitmask:
4949
// Bit 0: Emergency latch
50-
// Bit 1: Emergency 0 active
51-
// Bit 2: Emergency 1 active
52-
// Bit 3: Emergency 2 active
53-
// Bit 4: Emergency 3 active
50+
// Bit 1: Emergency/Lift (or tilt)
51+
// Bit 2: Emergency/Stop
5452
uint8_t emergency_bitmask;
5553
// Charge voltage
5654
float v_charge;
@@ -111,24 +109,74 @@ struct ll_high_level_state {
111109
} __attribute__((packed));
112110
#pragma pack(pop)
113111

114-
#define LL_HIGH_LEVEL_CONFIG_MAX_COMMS_VERSION 1 // Max. comms packet version supported by this open_mower_ros
115-
#define LL_HIGH_LEVEL_CONFIG_BIT_DFPIS5V 1 << 0 // Enable full sound via mower_config env var "OM_DFP_IS_5V"
116-
#define LL_HIGH_LEVEL_CONFIG_BIT_EMERGENCY_INVERSE \
117-
1 << 1 // Sample, for possible future usage, i.e. for SA-Type emergency
112+
enum class OptionState : unsigned int {
113+
OFF = 0,
114+
ON,
115+
UNDEFINED
116+
};
117+
118+
#pragma pack(push, 1)
119+
struct ConfigOptions {
120+
OptionState dfp_is_5v : 2;
121+
OptionState background_sounds : 2;
122+
OptionState ignore_charging_current : 2;
123+
// Need to block/waster the bits now, to be prepared for future enhancements
124+
OptionState reserved_for_future_use1 : 2;
125+
OptionState reserved_for_future_use2 : 2;
126+
OptionState reserved_for_future_use3 : 2;
127+
OptionState reserved_for_future_use4 : 2;
128+
OptionState reserved_for_future_use5 : 2;
129+
} __attribute__((packed));
130+
#pragma pack(pop)
131+
static_assert(sizeof(ConfigOptions) == 2, "Changing size of ConfigOption != 2 will break packet compatibilty");
118132

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

135+
enum class HallMode : unsigned int {
136+
OFF = 0,
137+
LIFT_TILT, // Wheel lifted and wheels tilted functionality
138+
STOP, // Stop mower
139+
UNDEFINED // This is used by foreign side to inform that it doesn't has a configuration for this sensor
140+
};
141+
142+
#pragma pack(push, 1)
143+
struct HallConfig {
144+
HallConfig(HallMode t_mode = HallMode::UNDEFINED, bool t_active_low = false)
145+
: mode(t_mode), active_low(t_active_low) {};
146+
147+
HallMode mode : 3; // 1 bit reserved
148+
bool active_low : 1;
149+
} __attribute__((packed));
150+
#pragma pack(pop)
151+
152+
#define MAX_HALL_INPUTS 10 // How much Hall-inputs we do support. 4 * OM + 6 * Stock-CoverUI
153+
154+
// LL/HL config packet, bi-directional, flexible-length
121155
#pragma pack(push, 1)
122156
struct ll_high_level_config {
123-
uint8_t type = PACKET_ID_LL_HIGH_LEVEL_CONFIG_RSP; // By default, respond only (for now)
124-
uint8_t comms_version = LL_HIGH_LEVEL_CONFIG_MAX_COMMS_VERSION; // Increasing comms packet-version number for packet
125-
// compatibility (n > 0)
126-
uint8_t config_bitmask = 0; // See LL_HIGH_LEVEL_CONFIG_BIT_*
127-
int8_t volume; // Volume (0-100%) feedback (if directly changed via CoverUI). -1 = don't change
128-
iso639_1 language; // ISO 639-1 (2-char) language code (en, de, ...)
129-
uint16_t spare1 = 0; // Spare for future use
130-
uint16_t spare2 = 0; // Spare for future use
131-
uint16_t crc;
157+
// ATTENTION: This is a flexible length struct. It is allowed to grow independently to HL without loosing
158+
// compatibility, but never change or restructure already published member, except you really know their consequences.
159+
160+
// uint8_t type; Just for illustration. Get set later in wire buffer with type PACKET_ID_LL_HIGH_LEVEL_CONFIG_*
161+
162+
// clang-format off
163+
ConfigOptions options = {.dfp_is_5v = OptionState::OFF, .background_sounds = OptionState::OFF, .ignore_charging_current = OptionState::OFF};
164+
uint16_t rain_threshold = 0xffff; // If (stock CoverUI) rain value < rain_threshold then it rains
165+
float v_charge_cutoff = -1; // Protective max. charging voltage before charging get switched off (-1 = unknown)
166+
float i_charge_cutoff = -1; // Protective max. charging current before charging get switched off (-1 = unknown)
167+
float v_battery_cutoff = -1; // Protective max. battery voltage before charging get switched off (-1 = unknown)
168+
float v_battery_empty = -1; // Empty battery voltage used for % calc of capacity (-1 = unknown)
169+
float v_battery_full = -1; // Full battery voltage used for % calc of capacity (-1 = unknown)
170+
uint16_t lift_period = 0xffff; // Period (ms) for >=2 wheels to be lifted in order to count as emergency (0 = disable, 0xFFFF = unknown)
171+
uint16_t tilt_period = 0xffff; // Period (ms) for a single wheel to be lifted in order to count as emergency (0 = disable, 0xFFFF = unknown)
172+
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)
173+
iso639_1 language = {'e', 'n'}; // ISO 639-1 (2-char) language code (en, de, ...)
174+
uint8_t volume = 0xff; // Volume (0-100%) feedback (if directly changed i.e. via CoverUI) (0xff = do not change)
175+
HallConfig hall_configs[MAX_HALL_INPUTS]; // Set all to UNDEFINED
176+
// INFO: Before adding a new member here: Decide if and how much hall_configs spares do we like to have
177+
178+
// uint16_t crc; Just for illustration, that it get appended later within the wire buffer
179+
// clang-format on
132180
} __attribute__((packed));
133181
#pragma pack(pop)
134182

0 commit comments

Comments
 (0)