Skip to content

Commit

Permalink
Add critical-high- battery and charging parameter
Browse files Browse the repository at this point in the history
  • Loading branch information
Apehaenger committed Oct 24, 2024
1 parent 082f29c commit 51f103b
Show file tree
Hide file tree
Showing 3 changed files with 32 additions and 1 deletion.
21 changes: 21 additions & 0 deletions config/mower_config.schema.json
Original file line number Diff line number Diff line change
Expand Up @@ -531,6 +531,27 @@
"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
8 changes: 8 additions & 0 deletions config/mower_config.sh.example
Original file line number Diff line number Diff line change
Expand Up @@ -196,6 +196,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
4 changes: 3 additions & 1 deletion src/open_mower/launch/open_mower.launch
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,6 @@

<arg name="battery_empty_voltage" value="$(env OM_BATTERY_EMPTY_VOLTAGE)" />
<arg name="battery_critical_voltage" value="$(optenv OM_BATTERY_CRITICAL_VOLTAGE)" />
<arg name="battery_critical_high_voltage" value="$(optenv OM_BATTERY_CRITICAL_HIGH_VOLTAGE)" />

<node pkg="mower_map" type="mower_map_service" name="map_service" output="screen"/>
<node pkg="mower_logic" type="mower_logic" name="mower_logic" output="screen">
Expand All @@ -29,6 +28,9 @@
value="$(eval battery_empty_voltage if battery_critical_voltage=='' else battery_critical_voltage)"
/>
<param name="battery_full_voltage" value="$(env OM_BATTERY_FULL_VOLTAGE)"/>
<param name="battery_critical_high_voltage" value="$(optenv OM_BATTERY_CRITICAL_HIGH_VOLTAGE -1)"/>
<param name="charge_critical_high_voltage" value="$(optenv OM_CHARGE_CRITICAL_HIGH_VOLTAGE -1)"/>
<param name="charge_critical_high_current" value="$(optenv OM_CHARGE_CRITICAL_HIGH_CURRENT -1)"/>
<param name="outline_count" value="$(env OM_OUTLINE_COUNT)"/>
<param name="outline_overlap_count" value="$(optenv OM_OUTLINE_OVERLAP_COUNT 0)"/>
<param name="outline_offset" value="$(env OM_OUTLINE_OFFSET)"/>
Expand Down

0 comments on commit 51f103b

Please sign in to comment.