diff --git a/src/mower_logic/cfg/MowerLogic.cfg b/src/mower_logic/cfg/MowerLogic.cfg index 436754f7..45e0bf3a 100755 --- a/src/mower_logic/cfg/MowerLogic.cfg +++ b/src/mower_logic/cfg/MowerLogic.cfg @@ -19,7 +19,8 @@ gen.add("mow_angle_increment", double_t, 0, "Mowing angle automatic increment. W gen.add("tool_width", double_t, 0, "Width of the mower", 0.14, 0.1, 2) gen.add("enable_mower", bool_t, 0, "True to enable mow motor", False) gen.add("manual_pause_mowing", bool_t, 0, "True to disable mowing automatically", False) -gen.add("battery_empty_voltage", double_t, 0, "Voltage to return to docking station", 25.0, 20.0, 32.0) +gen.add("battery_empty_voltage", double_t, 0, "Voltage to return to docking station (over 20s interval)", 24.0, 20.0, 32.0) +gen.add("battery_critical_voltage", double_t, 0, "Voltage to return to docking station (immediate)", 23.0, 20.0, 32.0) gen.add("battery_full_voltage", double_t, 0, "Voltage to start mowing again", 29.0, 20.0, 32.0) gen.add("motor_hot_temperature", double_t, 0, "Motor temperature to pause mowing", 70.0, 20.0, 150.0) gen.add("motor_cold_temperature", double_t, 0, "Motor temperature to allow mowing", 40.0, 20.0, 150.0) diff --git a/src/mower_logic/src/mower_logic/mower_logic.cpp b/src/mower_logic/src/mower_logic/mower_logic.cpp index 23bafd32..492a5345 100644 --- a/src/mower_logic/src/mower_logic/mower_logic.cpp +++ b/src/mower_logic/src/mower_logic/mower_logic.cpp @@ -51,6 +51,8 @@ #include "xbot_msgs/RegisterActionsSrv.h" #include #include +#include +#include ros::ServiceClient pathClient, mapClient, dockingPointClient, gpsClient, mowClient, emergencyClient, pathProgressClient, setNavPointClient, clearNavPointClient, clearMapClient, positioningClient, actionRegistrationClient; @@ -81,6 +83,8 @@ std::atomic mowerEnabled; Behavior *currentBehavior = &IdleBehavior::INSTANCE; +ros::Time last_v_battery_check; +double max_v_battery_seen = 0.0; /** * Some thread safe methods to get a copy of the logic state @@ -468,8 +472,32 @@ void checkSafety(const ros::TimerEvent &timer_event) { // we are in non emergency, check if we should pause. This could be empty battery, rain or hot mower motor etc. bool dockingNeeded = false; - if (last_status.v_battery < last_config.battery_empty_voltage || last_status.mow_esc_status.temperature_motor >= last_config.motor_hot_temperature || - last_config.manual_pause_mowing) { + std::stringstream dockingReason("Docking: ", std::ios_base::ate | std::ios_base::in | std::ios_base::out); + + if (last_config.manual_pause_mowing) { + dockingReason << "Manual pause"; + dockingNeeded = true; + } + + // Dock if below critical voltage to avoid BMS undervoltage protection + if(!dockingNeeded && (last_status.v_battery < last_config.battery_critical_voltage)) { + dockingReason << "Battery voltage min critical: " << last_status.v_battery; + dockingNeeded = true; + } + + // Otherwise take the max battery voltage over 20s to ignore droop during short current spikes + max_v_battery_seen = std::max(max_v_battery_seen, last_status.v_battery); + if (ros::Time::now() - last_v_battery_check > ros::Duration(20.0)) { + if(!dockingNeeded && (max_v_battery_seen < last_config.battery_empty_voltage)) { + dockingReason << "Battery average voltage low: " << max_v_battery_seen; + dockingNeeded = true; + } + max_v_battery_seen = 0.0; + last_v_battery_check = ros::Time::now(); + } + + if (!dockingNeeded && last_status.mow_esc_status.temperature_motor >= last_config.motor_hot_temperature) { + dockingReason << "Mow motor over temp: " << last_status.mow_esc_status.temperature_motor; dockingNeeded = true; } @@ -630,6 +658,7 @@ int main(int argc, char **argv) { } r.sleep(); } + ROS_INFO("Waiting for a pose message"); while (pose_time == ros::Time(0.0)) { if (!ros::ok()) { @@ -762,6 +791,7 @@ int main(int argc, char **argv) { + last_v_battery_check = ros::Time::now(); ros::Timer safety_timer = n->createTimer(ros::Duration(0.5), checkSafety); ros::Timer ui_timer = n->createTimer(ros::Duration(1.0), updateUI); diff --git a/src/open_mower/config/mower_config.sh.example b/src/open_mower/config/mower_config.sh.example index 8ce08bd6..8b6946b8 100644 --- a/src/open_mower/config/mower_config.sh.example +++ b/src/open_mower/config/mower_config.sh.example @@ -143,8 +143,11 @@ export OM_MOWING_ANGLE_INCREMENT=0 export OM_TOOL_WIDTH=0.13 # Voltages for battery to be considered full or empty -export OM_BATTERY_EMPTY_VOLTAGE=25.0 export OM_BATTERY_FULL_VOLTAGE=28.5 +# Dock if voltage remains below empty for 20s +export OM_BATTERY_EMPTY_VOLTAGE=24.0 +# Immediate dock if voltage is critical +export OM_BATTERY_CRITICAL_VOLTAGE=23.0 # Mower motor temperatures to stop and start mowing export OM_MOWING_MOTOR_TEMP_HIGH=80.0 diff --git a/src/open_mower/launch/open_mower.launch b/src/open_mower/launch/open_mower.launch index 02159e6b..47862226 100644 --- a/src/open_mower/launch/open_mower.launch +++ b/src/open_mower/launch/open_mower.launch @@ -7,6 +7,9 @@ + + + @@ -15,14 +18,18 @@ - + + + - diff --git a/src/open_mower/launch/sim_mower_logic.launch b/src/open_mower/launch/sim_mower_logic.launch index 2ffa4665..097c8ff1 100644 --- a/src/open_mower/launch/sim_mower_logic.launch +++ b/src/open_mower/launch/sim_mower_logic.launch @@ -7,6 +7,9 @@ + + + @@ -18,14 +21,18 @@ - + + + -