Copter: low battery msg to severity high

This commit is contained in:
Randy Mackay 2014-09-21 17:33:19 +09:00
parent 193bc5331a
commit e7753223ba
3 changed files with 6 additions and 6 deletions

View File

@ -156,9 +156,9 @@ process_logs(uint8_t argc, const Menu::arg *argv)
static void do_erase_logs(void)
{
gcs_send_text_P(SEVERITY_LOW, PSTR("Erasing logs\n"));
gcs_send_text_P(SEVERITY_HIGH, PSTR("Erasing logs\n"));
DataFlash.EraseAll();
gcs_send_text_P(SEVERITY_LOW, PSTR("Log erase complete\n"));
gcs_send_text_P(SEVERITY_HIGH, PSTR("Log erase complete\n"));
}
#if AUTOTUNE_ENABLED == ENABLED

View File

@ -164,7 +164,7 @@ static void failsafe_battery_event(void)
set_failsafe_battery(true);
// warn the ground station and log to dataflash
gcs_send_text_P(SEVERITY_LOW,PSTR("Low Battery!"));
gcs_send_text_P(SEVERITY_HIGH,PSTR("Low Battery!"));
Log_Write_Error(ERROR_SUBSYSTEM_FAILSAFE_BATT, ERROR_CODE_FAILSAFE_OCCURRED);
}
@ -205,7 +205,7 @@ static void failsafe_gps_check()
// GPS failsafe event has occured
// update state, warn the ground station and log to dataflash
set_failsafe_gps(true);
gcs_send_text_P(SEVERITY_LOW,PSTR("Lost GPS!"));
gcs_send_text_P(SEVERITY_HIGH,PSTR("Lost GPS!"));
Log_Write_Error(ERROR_SUBSYSTEM_FAILSAFE_GPS, ERROR_CODE_FAILSAFE_OCCURRED);
// take action based on flight mode and FS_GPS_ENABLED parameter

View File

@ -183,10 +183,10 @@ static void init_ardupilot()
#if LOGGING_ENABLED == ENABLED
DataFlash.Init(log_structure, sizeof(log_structure)/sizeof(log_structure[0]));
if (!DataFlash.CardInserted()) {
gcs_send_text_P(SEVERITY_LOW, PSTR("No dataflash inserted"));
gcs_send_text_P(SEVERITY_HIGH, PSTR("No dataflash inserted"));
g.log_bitmask.set(0);
} else if (DataFlash.NeedErase()) {
gcs_send_text_P(SEVERITY_LOW, PSTR("ERASING LOGS"));
gcs_send_text_P(SEVERITY_HIGH, PSTR("ERASING LOGS"));
do_erase_logs();
gcs[0].reset_cli_timeout();
}