Copter: move Log_Write_Error into library

This commit is contained in:
Peter Barker 2019-03-25 12:31:46 +11:00 committed by Peter Barker
parent 4d4a63cc33
commit c7e21d95ef
16 changed files with 47 additions and 129 deletions

View File

@ -724,7 +724,6 @@ private:
void Log_Write_Data(uint8_t id, int16_t value); void Log_Write_Data(uint8_t id, int16_t value);
void Log_Write_Data(uint8_t id, uint16_t value); void Log_Write_Data(uint8_t id, uint16_t value);
void Log_Write_Data(uint8_t id, float value); void Log_Write_Data(uint8_t id, float value);
void Log_Write_Error(uint8_t sub_system, uint8_t error_code);
void Log_Write_Parameter_Tuning(uint8_t param, float tuning_val, int16_t control_in, int16_t tune_low, int16_t tune_high); void Log_Write_Parameter_Tuning(uint8_t param, float tuning_val, int16_t control_in, int16_t tune_low, int16_t tune_high);
void Log_Sensor_Health(); void Log_Sensor_Health();
#if FRAME_CONFIG == HELI_FRAME #if FRAME_CONFIG == HELI_FRAME

View File

@ -229,25 +229,6 @@ void Copter::Log_Write_Data(uint8_t id, float value)
} }
} }
struct PACKED log_Error {
LOG_PACKET_HEADER;
uint64_t time_us;
uint8_t sub_system;
uint8_t error_code;
};
// Write an error packet
void Copter::Log_Write_Error(uint8_t sub_system, uint8_t error_code)
{
struct log_Error pkt = {
LOG_PACKET_HEADER_INIT(LOG_ERROR_MSG),
time_us : AP_HAL::micros64(),
sub_system : sub_system,
error_code : error_code,
};
logger.WriteCriticalBlock(&pkt, sizeof(pkt));
}
struct PACKED log_ParameterTuning { struct PACKED log_ParameterTuning {
LOG_PACKET_HEADER; LOG_PACKET_HEADER;
uint64_t time_us; uint64_t time_us;
@ -279,13 +260,14 @@ void Copter::Log_Sensor_Health()
// check baro // check baro
if (sensor_health.baro != barometer.healthy()) { if (sensor_health.baro != barometer.healthy()) {
sensor_health.baro = barometer.healthy(); sensor_health.baro = barometer.healthy();
Log_Write_Error(ERROR_SUBSYSTEM_BARO, (sensor_health.baro ? ERROR_CODE_ERROR_RESOLVED : ERROR_CODE_UNHEALTHY)); AP::logger().Write_Error(LogErrorSubsystem::BARO,
(sensor_health.baro ? LogErrorCode::ERROR_RESOLVED : LogErrorCode::UNHEALTHY));
} }
// check compass // check compass
if (sensor_health.compass != compass.healthy()) { if (sensor_health.compass != compass.healthy()) {
sensor_health.compass = compass.healthy(); sensor_health.compass = compass.healthy();
Log_Write_Error(ERROR_SUBSYSTEM_COMPASS, (sensor_health.compass ? ERROR_CODE_ERROR_RESOLVED : ERROR_CODE_UNHEALTHY)); AP::logger().Write_Error(LogErrorSubsystem::COMPASS, (sensor_health.compass ? LogErrorCode::ERROR_RESOLVED : LogErrorCode::UNHEALTHY));
} }
// check primary GPS // check primary GPS
@ -421,8 +403,6 @@ const struct LogStructure Copter::log_structure[] = {
"DU32", "QBI", "TimeUS,Id,Value", "s--", "F--" }, "DU32", "QBI", "TimeUS,Id,Value", "s--", "F--" },
{ LOG_DATA_FLOAT_MSG, sizeof(log_Data_Float), { LOG_DATA_FLOAT_MSG, sizeof(log_Data_Float),
"DFLT", "QBf", "TimeUS,Id,Value", "s--", "F--" }, "DFLT", "QBf", "TimeUS,Id,Value", "s--", "F--" },
{ LOG_ERROR_MSG, sizeof(log_Error),
"ERR", "QBB", "TimeUS,Subsys,ECode", "s--", "F--" },
#if FRAME_CONFIG == HELI_FRAME #if FRAME_CONFIG == HELI_FRAME
{ LOG_HELI_MSG, sizeof(log_Heli), { LOG_HELI_MSG, sizeof(log_Heli),
"HELI", "Qff", "TimeUS,DRRPM,ERRPM", "s--", "F--" }, "HELI", "Qff", "TimeUS,DRRPM,ERRPM", "s--", "F--" },
@ -463,7 +443,6 @@ void Copter::Log_Write_Data(uint8_t id, uint32_t value) {}
void Copter::Log_Write_Data(uint8_t id, int16_t value) {} void Copter::Log_Write_Data(uint8_t id, int16_t value) {}
void Copter::Log_Write_Data(uint8_t id, uint16_t value) {} void Copter::Log_Write_Data(uint8_t id, uint16_t value) {}
void Copter::Log_Write_Data(uint8_t id, float value) {} void Copter::Log_Write_Data(uint8_t id, float value) {}
void Copter::Log_Write_Error(uint8_t sub_system, uint8_t error_code) {}
void Copter::Log_Write_Parameter_Tuning(uint8_t param, float tuning_val, int16_t control_in, int16_t tune_low, int16_t tune_high) {} void Copter::Log_Write_Parameter_Tuning(uint8_t param, float tuning_val, int16_t control_in, int16_t tune_low, int16_t tune_high) {}
void Copter::Log_Sensor_Health() {} void Copter::Log_Sensor_Health() {}
void Copter::Log_Write_Precland() {} void Copter::Log_Write_Precland() {}

View File

@ -90,7 +90,8 @@ MAV_COLLISION_ACTION AP_Avoidance_Copter::handle_avoidance(const AP_Avoidance::O
// log to dataflash // log to dataflash
if (failsafe_state_change) { if (failsafe_state_change) {
copter.Log_Write_Error(ERROR_SUBSYSTEM_FAILSAFE_ADSB, actual_action); AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_ADSB,
LogErrorCode(actual_action));
} }
// return with action taken // return with action taken
@ -102,7 +103,8 @@ void AP_Avoidance_Copter::handle_recovery(uint8_t recovery_action)
// check we are coming out of failsafe // check we are coming out of failsafe
if (copter.failsafe.adsb) { if (copter.failsafe.adsb) {
copter.failsafe.adsb = false; copter.failsafe.adsb = false;
copter.Log_Write_Error(ERROR_SUBSYSTEM_FAILSAFE_ADSB, ERROR_CODE_ERROR_RESOLVED); AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_ADSB,
LogErrorCode::ERROR_RESOLVED);
// restore flight mode if requested and user has not changed mode since // restore flight mode if requested and user has not changed mode since
if (copter.control_mode_reason == MODE_REASON_AVOIDANCE) { if (copter.control_mode_reason == MODE_REASON_AVOIDANCE) {

View File

@ -48,7 +48,7 @@ void Copter::crash_check()
// check if crashing for 2 seconds // check if crashing for 2 seconds
if (crash_counter >= (CRASH_CHECK_TRIGGER_SEC * scheduler.get_loop_rate_hz())) { if (crash_counter >= (CRASH_CHECK_TRIGGER_SEC * scheduler.get_loop_rate_hz())) {
// log an error in the dataflash // log an error in the dataflash
Log_Write_Error(ERROR_SUBSYSTEM_CRASH_CHECK, ERROR_CODE_CRASH_CHECK_CRASH); AP::logger().Write_Error(LogErrorSubsystem::CRASH_CHECK, LogErrorCode::CRASH_CHECK_CRASH);
// keep logging even if disarmed: // keep logging even if disarmed:
AP::logger().set_force_log_disarmed(true); AP::logger().set_force_log_disarmed(true);
// send message to gcs // send message to gcs
@ -116,7 +116,7 @@ void Copter::thrust_loss_check()
// reset counter // reset counter
thrust_loss_counter = 0; thrust_loss_counter = 0;
// log an error in the dataflash // log an error in the dataflash
Log_Write_Error(ERROR_SUBSYSTEM_THRUST_LOSS_CHECK, ERROR_CODE_FAILSAFE_OCCURRED); AP::logger().Write_Error(LogErrorSubsystem::THRUST_LOSS_CHECK, LogErrorCode::FAILSAFE_OCCURRED);
// send message to gcs // send message to gcs
gcs().send_text(MAV_SEVERITY_EMERGENCY, "Potential Thrust Loss (%d)", (int)motors->get_lost_motor() + 1); gcs().send_text(MAV_SEVERITY_EMERGENCY, "Potential Thrust Loss (%d)", (int)motors->get_lost_motor() + 1);
// enable thrust loss handling // enable thrust loss handling
@ -200,7 +200,7 @@ void Copter::parachute_check()
// reset control loss counter // reset control loss counter
control_loss_count = 0; control_loss_count = 0;
// log an error in the dataflash // log an error in the dataflash
Log_Write_Error(ERROR_SUBSYSTEM_CRASH_CHECK, ERROR_CODE_CRASH_CHECK_LOSS_OF_CONTROL); AP::logger().Write_Error(LogErrorSubsystem::CRASH_CHECK, LogErrorCode::CRASH_CHECK_LOSS_OF_CONTROL);
// release parachute // release parachute
parachute_release(); parachute_release();
} }
@ -234,7 +234,7 @@ void Copter::parachute_manual_release()
// warn user of reason for failure // warn user of reason for failure
gcs().send_text(MAV_SEVERITY_INFO,"Parachute: Landed"); gcs().send_text(MAV_SEVERITY_INFO,"Parachute: Landed");
// log an error in the dataflash // log an error in the dataflash
Log_Write_Error(ERROR_SUBSYSTEM_PARACHUTE, ERROR_CODE_PARACHUTE_LANDED); AP::logger().Write_Error(LogErrorSubsystem::PARACHUTES, LogErrorCode::PARACHUTE_LANDED);
return; return;
} }
@ -243,7 +243,7 @@ void Copter::parachute_manual_release()
// warn user of reason for failure // warn user of reason for failure
gcs().send_text(MAV_SEVERITY_ALERT,"Parachute: Too low"); gcs().send_text(MAV_SEVERITY_ALERT,"Parachute: Too low");
// log an error in the dataflash // log an error in the dataflash
Log_Write_Error(ERROR_SUBSYSTEM_PARACHUTE, ERROR_CODE_PARACHUTE_TOO_LOW); AP::logger().Write_Error(LogErrorSubsystem::PARACHUTES, LogErrorCode::PARACHUTE_TOO_LOW);
return; return;
} }

View File

@ -240,7 +240,6 @@ enum LoggingParameters {
TYPE_AIRSTART_MSG, TYPE_AIRSTART_MSG,
TYPE_GROUNDSTART_MSG, TYPE_GROUNDSTART_MSG,
LOG_CONTROL_TUNING_MSG, LOG_CONTROL_TUNING_MSG,
LOG_ERROR_MSG,
LOG_DATA_INT16_MSG, LOG_DATA_INT16_MSG,
LOG_DATA_UINT16_MSG, LOG_DATA_UINT16_MSG,
LOG_DATA_INT32_MSG, LOG_DATA_INT32_MSG,
@ -274,67 +273,6 @@ enum LoggingParameters {
#define MASK_LOG_IMU_RAW (1UL<<19) #define MASK_LOG_IMU_RAW (1UL<<19)
#define MASK_LOG_ANY 0xFFFF #define MASK_LOG_ANY 0xFFFF
// Error message sub systems and error codes
#define ERROR_SUBSYSTEM_MAIN 1
#define ERROR_SUBSYSTEM_RADIO 2
#define ERROR_SUBSYSTEM_COMPASS 3
#define ERROR_SUBSYSTEM_OPTFLOW 4 // not used
#define ERROR_SUBSYSTEM_FAILSAFE_RADIO 5
#define ERROR_SUBSYSTEM_FAILSAFE_BATT 6
#define ERROR_SUBSYSTEM_FAILSAFE_GPS 7 // not used
#define ERROR_SUBSYSTEM_FAILSAFE_GCS 8
#define ERROR_SUBSYSTEM_FAILSAFE_FENCE 9
#define ERROR_SUBSYSTEM_FLIGHT_MODE 10
#define ERROR_SUBSYSTEM_GPS 11
#define ERROR_SUBSYSTEM_CRASH_CHECK 12
#define ERROR_SUBSYSTEM_FLIP 13
#define ERROR_SUBSYSTEM_AUTOTUNE 14 // not used
#define ERROR_SUBSYSTEM_PARACHUTE 15
#define ERROR_SUBSYSTEM_EKFCHECK 16
#define ERROR_SUBSYSTEM_FAILSAFE_EKFINAV 17
#define ERROR_SUBSYSTEM_BARO 18
#define ERROR_SUBSYSTEM_CPU 19
#define ERROR_SUBSYSTEM_FAILSAFE_ADSB 20
#define ERROR_SUBSYSTEM_TERRAIN 21
#define ERROR_SUBSYSTEM_NAVIGATION 22
#define ERROR_SUBSYSTEM_FAILSAFE_TERRAIN 23
#define ERROR_SUBSYSTEM_EKF_PRIMARY 24
#define ERROR_SUBSYSTEM_THRUST_LOSS_CHECK 25
// general error codes
#define ERROR_CODE_ERROR_RESOLVED 0
#define ERROR_CODE_FAILED_TO_INITIALISE 1
#define ERROR_CODE_UNHEALTHY 4
// subsystem specific error codes -- radio
#define ERROR_CODE_RADIO_LATE_FRAME 2
// subsystem specific error codes -- failsafe_thr, batt, gps
#define ERROR_CODE_FAILSAFE_RESOLVED 0
#define ERROR_CODE_FAILSAFE_OCCURRED 1
// subsystem specific error codes -- main
#define ERROR_CODE_MAIN_INS_DELAY 1
// subsystem specific error codes -- crash checker
#define ERROR_CODE_CRASH_CHECK_CRASH 1
#define ERROR_CODE_CRASH_CHECK_LOSS_OF_CONTROL 2
// subsystem specific error codes -- flip
#define ERROR_CODE_FLIP_ABANDONED 2
// subsystem specific error codes -- terrain
#define ERROR_CODE_MISSING_TERRAIN_DATA 2
// subsystem specific error codes -- navigation
#define ERROR_CODE_FAILED_TO_SET_DESTINATION 2
#define ERROR_CODE_RESTARTED_RTL 3
#define ERROR_CODE_FAILED_CIRCLE_INIT 4
#define ERROR_CODE_DEST_OUTSIDE_FENCE 5
// parachute failed to deploy because of low altitude or landed
#define ERROR_CODE_PARACHUTE_TOO_LOW 2
#define ERROR_CODE_PARACHUTE_LANDED 3
// EKF check definitions
#define ERROR_CODE_EKFCHECK_BAD_VARIANCE 2
#define ERROR_CODE_EKFCHECK_VARIANCE_CLEARED 0
// Baro specific error codes
#define ERROR_CODE_BARO_GLITCH 2
// GPS specific error coces
#define ERROR_CODE_GPS_GLITCH 2
// Radio failsafe definitions (FS_THR parameter) // Radio failsafe definitions (FS_THR parameter)
#define FS_THR_DISABLED 0 #define FS_THR_DISABLED 0
#define FS_THR_ENABLED_ALWAYS_RTL 1 #define FS_THR_ENABLED_ALWAYS_RTL 1

View File

@ -55,7 +55,7 @@ void Copter::ekf_check()
ekf_check_state.fail_count = EKF_CHECK_ITERATIONS_MAX; ekf_check_state.fail_count = EKF_CHECK_ITERATIONS_MAX;
ekf_check_state.bad_variance = true; ekf_check_state.bad_variance = true;
// log an error in the dataflash // log an error in the dataflash
Log_Write_Error(ERROR_SUBSYSTEM_EKFCHECK, ERROR_CODE_EKFCHECK_BAD_VARIANCE); AP::logger().Write_Error(LogErrorSubsystem::EKFCHECK, LogErrorCode::EKFCHECK_BAD_VARIANCE);
// send message to gcs // send message to gcs
if ((AP_HAL::millis() - ekf_check_state.last_warn_time) > EKF_CHECK_WARNING_TIME) { if ((AP_HAL::millis() - ekf_check_state.last_warn_time) > EKF_CHECK_WARNING_TIME) {
gcs().send_text(MAV_SEVERITY_CRITICAL,"EKF variance"); gcs().send_text(MAV_SEVERITY_CRITICAL,"EKF variance");
@ -73,7 +73,7 @@ void Copter::ekf_check()
if (ekf_check_state.bad_variance && ekf_check_state.fail_count == 0) { if (ekf_check_state.bad_variance && ekf_check_state.fail_count == 0) {
ekf_check_state.bad_variance = false; ekf_check_state.bad_variance = false;
// log recovery in the dataflash // log recovery in the dataflash
Log_Write_Error(ERROR_SUBSYSTEM_EKFCHECK, ERROR_CODE_EKFCHECK_VARIANCE_CLEARED); AP::logger().Write_Error(LogErrorSubsystem::EKFCHECK, LogErrorCode::EKFCHECK_VARIANCE_CLEARED);
// clear failsafe // clear failsafe
failsafe_ekf_off_event(); failsafe_ekf_off_event();
} }
@ -136,7 +136,7 @@ void Copter::failsafe_ekf_event()
// EKF failsafe event has occurred // EKF failsafe event has occurred
failsafe.ekf = true; failsafe.ekf = true;
Log_Write_Error(ERROR_SUBSYSTEM_FAILSAFE_EKFINAV, ERROR_CODE_FAILSAFE_OCCURRED); AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_EKFINAV, LogErrorCode::FAILSAFE_OCCURRED);
// sometimes LAND *does* require GPS so ensure we are in non-GPS land // sometimes LAND *does* require GPS so ensure we are in non-GPS land
if (control_mode == LAND && landing_with_GPS()) { if (control_mode == LAND && landing_with_GPS()) {
@ -175,7 +175,7 @@ void Copter::failsafe_ekf_off_event(void)
// clear flag and log recovery // clear flag and log recovery
failsafe.ekf = false; failsafe.ekf = false;
Log_Write_Error(ERROR_SUBSYSTEM_FAILSAFE_EKFINAV, ERROR_CODE_FAILSAFE_RESOLVED); AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_EKFINAV, LogErrorCode::FAILSAFE_RESOLVED);
} }
// check for ekf yaw reset and adjust target heading, also log position reset // check for ekf yaw reset and adjust target heading, also log position reset
@ -195,7 +195,7 @@ void Copter::check_ekf_reset()
if ((EKF2.getPrimaryCoreIndex() != ekf_primary_core) && (EKF2.getPrimaryCoreIndex() != -1)) { if ((EKF2.getPrimaryCoreIndex() != ekf_primary_core) && (EKF2.getPrimaryCoreIndex() != -1)) {
attitude_control->inertial_frame_reset(); attitude_control->inertial_frame_reset();
ekf_primary_core = EKF2.getPrimaryCoreIndex(); ekf_primary_core = EKF2.getPrimaryCoreIndex();
Log_Write_Error(ERROR_SUBSYSTEM_EKF_PRIMARY, ekf_primary_core); AP::logger().Write_Error(LogErrorSubsystem::EKF_PRIMARY, LogErrorCode(ekf_primary_core));
gcs().send_text(MAV_SEVERITY_WARNING, "EKF primary changed:%d", (unsigned)ekf_primary_core); gcs().send_text(MAV_SEVERITY_WARNING, "EKF primary changed:%d", (unsigned)ekf_primary_core);
} }
#endif #endif

View File

@ -36,7 +36,7 @@ void Copter::failsafe_radio_on_event()
} }
// log the error to the dataflash // log the error to the dataflash
Log_Write_Error(ERROR_SUBSYSTEM_FAILSAFE_RADIO, ERROR_CODE_FAILSAFE_OCCURRED); AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_RADIO, LogErrorCode::FAILSAFE_OCCURRED);
} }
@ -47,12 +47,12 @@ void Copter::failsafe_radio_off_event()
{ {
// no need to do anything except log the error as resolved // no need to do anything except log the error as resolved
// user can now override roll, pitch, yaw and throttle and even use flight mode switch to restore previous flight mode // user can now override roll, pitch, yaw and throttle and even use flight mode switch to restore previous flight mode
Log_Write_Error(ERROR_SUBSYSTEM_FAILSAFE_RADIO, ERROR_CODE_FAILSAFE_RESOLVED); AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_RADIO, LogErrorCode::FAILSAFE_RESOLVED);
} }
void Copter::handle_battery_failsafe(const char *type_str, const int8_t action) void Copter::handle_battery_failsafe(const char *type_str, const int8_t action)
{ {
Log_Write_Error(ERROR_SUBSYSTEM_FAILSAFE_BATT, ERROR_CODE_FAILSAFE_OCCURRED); AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_BATT, LogErrorCode::FAILSAFE_OCCURRED);
// failsafe check // failsafe check
if (should_disarm_on_failsafe()) { if (should_disarm_on_failsafe()) {
@ -118,7 +118,7 @@ void Copter::failsafe_gcs_check()
// GCS failsafe event has occurred // GCS failsafe event has occurred
// update state, log to dataflash // update state, log to dataflash
set_failsafe_gcs(true); set_failsafe_gcs(true);
Log_Write_Error(ERROR_SUBSYSTEM_FAILSAFE_GCS, ERROR_CODE_FAILSAFE_OCCURRED); AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_GCS, LogErrorCode::FAILSAFE_OCCURRED);
// clear overrides so that RC control can be regained with radio. // clear overrides so that RC control can be regained with radio.
RC_Channels::clear_overrides(); RC_Channels::clear_overrides();
@ -142,7 +142,7 @@ void Copter::failsafe_gcs_check()
void Copter::failsafe_gcs_off_event(void) void Copter::failsafe_gcs_off_event(void)
{ {
// log recovery of GCS in logs? // log recovery of GCS in logs?
Log_Write_Error(ERROR_SUBSYSTEM_FAILSAFE_GCS, ERROR_CODE_FAILSAFE_RESOLVED); AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_GCS, LogErrorCode::FAILSAFE_RESOLVED);
} }
// executes terrain failsafe if data is missing for longer than a few seconds // executes terrain failsafe if data is missing for longer than a few seconds
@ -159,7 +159,7 @@ void Copter::failsafe_terrain_check()
if (trigger_event) { if (trigger_event) {
failsafe_terrain_on_event(); failsafe_terrain_on_event();
} else { } else {
Log_Write_Error(ERROR_SUBSYSTEM_FAILSAFE_TERRAIN, ERROR_CODE_ERROR_RESOLVED); AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_TERRAIN, LogErrorCode::ERROR_RESOLVED);
failsafe.terrain = false; failsafe.terrain = false;
} }
} }
@ -190,7 +190,7 @@ void Copter::failsafe_terrain_on_event()
{ {
failsafe.terrain = true; failsafe.terrain = true;
gcs().send_text(MAV_SEVERITY_CRITICAL,"Failsafe: Terrain data missing"); gcs().send_text(MAV_SEVERITY_CRITICAL,"Failsafe: Terrain data missing");
Log_Write_Error(ERROR_SUBSYSTEM_FAILSAFE_TERRAIN, ERROR_CODE_FAILSAFE_OCCURRED); AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_TERRAIN, LogErrorCode::FAILSAFE_OCCURRED);
if (should_disarm_on_failsafe()) { if (should_disarm_on_failsafe()) {
init_disarm_motors(); init_disarm_motors();
@ -214,10 +214,10 @@ void Copter::gpsglitch_check()
if (ap.gps_glitching != gps_glitching) { if (ap.gps_glitching != gps_glitching) {
ap.gps_glitching = gps_glitching; ap.gps_glitching = gps_glitching;
if (gps_glitching) { if (gps_glitching) {
Log_Write_Error(ERROR_SUBSYSTEM_GPS, ERROR_CODE_GPS_GLITCH); AP::logger().Write_Error(LogErrorSubsystem::GPS, LogErrorCode::GPS_GLITCH);
gcs().send_text(MAV_SEVERITY_CRITICAL,"GPS Glitch"); gcs().send_text(MAV_SEVERITY_CRITICAL,"GPS Glitch");
} else { } else {
Log_Write_Error(ERROR_SUBSYSTEM_GPS, ERROR_CODE_ERROR_RESOLVED); AP::logger().Write_Error(LogErrorSubsystem::GPS, LogErrorCode::ERROR_RESOLVED);
gcs().send_text(MAV_SEVERITY_CRITICAL,"GPS Glitch cleared"); gcs().send_text(MAV_SEVERITY_CRITICAL,"GPS Glitch cleared");
} }
} }

View File

@ -43,7 +43,7 @@ void Copter::failsafe_check()
failsafe_last_timestamp = tnow; failsafe_last_timestamp = tnow;
if (in_failsafe) { if (in_failsafe) {
in_failsafe = false; in_failsafe = false;
Log_Write_Error(ERROR_SUBSYSTEM_CPU,ERROR_CODE_FAILSAFE_RESOLVED); AP::logger().Write_Error(LogErrorSubsystem::CPU, LogErrorCode::FAILSAFE_RESOLVED);
} }
return; return;
} }
@ -58,7 +58,7 @@ void Copter::failsafe_check()
motors->output_min(); motors->output_min();
} }
// log an error // log an error
Log_Write_Error(ERROR_SUBSYSTEM_CPU,ERROR_CODE_FAILSAFE_OCCURRED); AP::logger().Write_Error(LogErrorSubsystem::CPU, LogErrorCode::FAILSAFE_OCCURRED);
} }
if (failsafe_enabled && in_failsafe && tnow - failsafe_last_timestamp > 1000000) { if (failsafe_enabled && in_failsafe && tnow - failsafe_last_timestamp > 1000000) {

View File

@ -70,11 +70,11 @@ void Copter::fence_check()
} }
// log an error in the dataflash // log an error in the dataflash
Log_Write_Error(ERROR_SUBSYSTEM_FAILSAFE_FENCE, new_breaches); AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_FENCE, LogErrorCode(new_breaches));
} else if (orig_breaches) { } else if (orig_breaches) {
// record clearing of breach // record clearing of breach
Log_Write_Error(ERROR_SUBSYSTEM_FAILSAFE_FENCE, ERROR_CODE_ERROR_RESOLVED); AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_FENCE, LogErrorCode::ERROR_RESOLVED);
} }
} }

View File

@ -184,7 +184,7 @@ bool Copter::set_mode(control_mode_t mode, mode_reason_t reason)
Copter::Mode *new_flightmode = mode_from_mode_num(mode); Copter::Mode *new_flightmode = mode_from_mode_num(mode);
if (new_flightmode == nullptr) { if (new_flightmode == nullptr) {
gcs().send_text(MAV_SEVERITY_WARNING,"No such mode"); gcs().send_text(MAV_SEVERITY_WARNING,"No such mode");
Log_Write_Error(ERROR_SUBSYSTEM_FLIGHT_MODE,mode); AP::logger().Write_Error(LogErrorSubsystem::FLIGHT_MODE, LogErrorCode(mode));
return false; return false;
} }
@ -195,7 +195,7 @@ bool Copter::set_mode(control_mode_t mode, mode_reason_t reason)
// rotor runup is not complete // rotor runup is not complete
if (!ignore_checks && !new_flightmode->has_manual_throttle() && !motors->rotor_runup_complete()){ if (!ignore_checks && !new_flightmode->has_manual_throttle() && !motors->rotor_runup_complete()){
gcs().send_text(MAV_SEVERITY_WARNING,"Flight mode change failed"); gcs().send_text(MAV_SEVERITY_WARNING,"Flight mode change failed");
Log_Write_Error(ERROR_SUBSYSTEM_FLIGHT_MODE,mode); AP::logger().Write_Error(LogErrorSubsystem::FLIGHT_MODE, LogErrorCode(mode));
return false; return false;
} }
#endif #endif
@ -220,13 +220,13 @@ bool Copter::set_mode(control_mode_t mode, mode_reason_t reason)
new_flightmode->requires_GPS() && new_flightmode->requires_GPS() &&
!copter.position_ok()) { !copter.position_ok()) {
gcs().send_text(MAV_SEVERITY_WARNING, "Mode change failed: %s requires position", new_flightmode->name()); gcs().send_text(MAV_SEVERITY_WARNING, "Mode change failed: %s requires position", new_flightmode->name());
Log_Write_Error(ERROR_SUBSYSTEM_FLIGHT_MODE,mode); AP::logger().Write_Error(LogErrorSubsystem::FLIGHT_MODE, LogErrorCode(mode));
return false; return false;
} }
if (!new_flightmode->init(ignore_checks)) { if (!new_flightmode->init(ignore_checks)) {
gcs().send_text(MAV_SEVERITY_WARNING,"Flight mode change failed"); gcs().send_text(MAV_SEVERITY_WARNING,"Flight mode change failed");
Log_Write_Error(ERROR_SUBSYSTEM_FLIGHT_MODE,mode); AP::logger().Write_Error(LogErrorSubsystem::FLIGHT_MODE, LogErrorCode(mode));
return false; return false;
} }

View File

@ -151,7 +151,7 @@ void Copter::ModeAuto::takeoff_start(const Location& dest_loc)
int32_t alt_target; int32_t alt_target;
if (!dest.get_alt_cm(Location::AltFrame::ABOVE_HOME, alt_target)) { if (!dest.get_alt_cm(Location::AltFrame::ABOVE_HOME, alt_target)) {
// this failure could only happen if take-off alt was specified as an alt-above terrain and we have no terrain data // this failure could only happen if take-off alt was specified as an alt-above terrain and we have no terrain data
copter.Log_Write_Error(ERROR_SUBSYSTEM_TERRAIN, ERROR_CODE_MISSING_TERRAIN_DATA); AP::logger().Write_Error(LogErrorSubsystem::TERRAIN, LogErrorCode::MISSING_TERRAIN_DATA);
// fall back to altitude above current altitude // fall back to altitude above current altitude
alt_target = copter.current_loc.alt + dest.alt; alt_target = copter.current_loc.alt + dest.alt;
} }
@ -254,7 +254,7 @@ void Copter::ModeAuto::circle_movetoedge_start(const Location &circle_center, fl
if (!circle_center.get_vector_from_origin_NEU(circle_center_neu)) { if (!circle_center.get_vector_from_origin_NEU(circle_center_neu)) {
// default to current position and log error // default to current position and log error
circle_center_neu = inertial_nav.get_position(); circle_center_neu = inertial_nav.get_position();
copter.Log_Write_Error(ERROR_SUBSYSTEM_NAVIGATION, ERROR_CODE_FAILED_CIRCLE_INIT); AP::logger().Write_Error(LogErrorSubsystem::NAVIGATION, LogErrorCode::FAILED_CIRCLE_INIT);
} }
copter.circle_nav->set_center(circle_center_neu); copter.circle_nav->set_center(circle_center_neu);

View File

@ -205,7 +205,7 @@ void Copter::ModeFlip::run()
copter.set_mode(STABILIZE, MODE_REASON_UNKNOWN); copter.set_mode(STABILIZE, MODE_REASON_UNKNOWN);
} }
// log abandoning flip // log abandoning flip
copter.Log_Write_Error(ERROR_SUBSYSTEM_FLIP,ERROR_CODE_FLIP_ABANDONED); AP::logger().Write_Error(LogErrorSubsystem::FLIP, LogErrorCode::FLIP_ABANDONED);
break; break;
} }

View File

@ -57,7 +57,7 @@ bool Copter::ModeGuided::do_user_takeoff_start(float final_alt_above_home)
if (!wp_nav->set_wp_destination(target_loc)) { if (!wp_nav->set_wp_destination(target_loc)) {
// failure to set destination can only be because of missing terrain data // failure to set destination can only be because of missing terrain data
copter.Log_Write_Error(ERROR_SUBSYSTEM_NAVIGATION, ERROR_CODE_FAILED_TO_SET_DESTINATION); AP::logger().Write_Error(LogErrorSubsystem::NAVIGATION, LogErrorCode::FAILED_TO_SET_DESTINATION);
// failure is propagated to GCS with NAK // failure is propagated to GCS with NAK
return false; return false;
} }
@ -187,7 +187,7 @@ bool Copter::ModeGuided::set_destination(const Vector3f& destination, bool use_y
// reject destination if outside the fence // reject destination if outside the fence
const Location dest_loc(destination); const Location dest_loc(destination);
if (!copter.fence.check_destination_within_fence(dest_loc)) { if (!copter.fence.check_destination_within_fence(dest_loc)) {
copter.Log_Write_Error(ERROR_SUBSYSTEM_NAVIGATION, ERROR_CODE_DEST_OUTSIDE_FENCE); AP::logger().Write_Error(LogErrorSubsystem::NAVIGATION, LogErrorCode::DEST_OUTSIDE_FENCE);
// failure is propagated to GCS with NAK // failure is propagated to GCS with NAK
return false; return false;
} }
@ -226,7 +226,7 @@ bool Copter::ModeGuided::set_destination(const Location& dest_loc, bool use_yaw,
// reject destination outside the fence. // reject destination outside the fence.
// Note: there is a danger that a target specified as a terrain altitude might not be checked if the conversion to alt-above-home fails // Note: there is a danger that a target specified as a terrain altitude might not be checked if the conversion to alt-above-home fails
if (!copter.fence.check_destination_within_fence(dest_loc)) { if (!copter.fence.check_destination_within_fence(dest_loc)) {
copter.Log_Write_Error(ERROR_SUBSYSTEM_NAVIGATION, ERROR_CODE_DEST_OUTSIDE_FENCE); AP::logger().Write_Error(LogErrorSubsystem::NAVIGATION, LogErrorCode::DEST_OUTSIDE_FENCE);
// failure is propagated to GCS with NAK // failure is propagated to GCS with NAK
return false; return false;
} }
@ -234,7 +234,7 @@ bool Copter::ModeGuided::set_destination(const Location& dest_loc, bool use_yaw,
if (!wp_nav->set_wp_destination(dest_loc)) { if (!wp_nav->set_wp_destination(dest_loc)) {
// failure to set destination can only be because of missing terrain data // failure to set destination can only be because of missing terrain data
copter.Log_Write_Error(ERROR_SUBSYSTEM_NAVIGATION, ERROR_CODE_FAILED_TO_SET_DESTINATION); AP::logger().Write_Error(LogErrorSubsystem::NAVIGATION, LogErrorCode::FAILED_TO_SET_DESTINATION);
// failure is propagated to GCS with NAK // failure is propagated to GCS with NAK
return false; return false;
} }
@ -280,7 +280,7 @@ bool Copter::ModeGuided::set_destination_posvel(const Vector3f& destination, con
// reject destination if outside the fence // reject destination if outside the fence
const Location dest_loc(destination); const Location dest_loc(destination);
if (!copter.fence.check_destination_within_fence(dest_loc)) { if (!copter.fence.check_destination_within_fence(dest_loc)) {
copter.Log_Write_Error(ERROR_SUBSYSTEM_NAVIGATION, ERROR_CODE_DEST_OUTSIDE_FENCE); AP::logger().Write_Error(LogErrorSubsystem::NAVIGATION, LogErrorCode::DEST_OUTSIDE_FENCE);
// failure is propagated to GCS with NAK // failure is propagated to GCS with NAK
return false; return false;
} }

View File

@ -23,7 +23,7 @@ bool Copter::ModeRTL::init(bool ignore_checks)
void Copter::ModeRTL::restart_without_terrain() void Copter::ModeRTL::restart_without_terrain()
{ {
// log an error // log an error
copter.Log_Write_Error(ERROR_SUBSYSTEM_NAVIGATION, ERROR_CODE_RESTARTED_RTL); AP::logger().Write_Error(LogErrorSubsystem::NAVIGATION, LogErrorCode::RESTARTED_RTL);
if (rtl_path.terrain_used) { if (rtl_path.terrain_used) {
build_path(false); build_path(false);
climb_start(); climb_start();
@ -99,7 +99,7 @@ void Copter::ModeRTL::climb_start()
// set the destination // set the destination
if (!wp_nav->set_wp_destination(rtl_path.climb_target)) { if (!wp_nav->set_wp_destination(rtl_path.climb_target)) {
// this should not happen because rtl_build_path will have checked terrain data was available // this should not happen because rtl_build_path will have checked terrain data was available
copter.Log_Write_Error(ERROR_SUBSYSTEM_NAVIGATION, ERROR_CODE_FAILED_TO_SET_DESTINATION); AP::logger().Write_Error(LogErrorSubsystem::NAVIGATION, LogErrorCode::FAILED_TO_SET_DESTINATION);
copter.set_mode(LAND, MODE_REASON_TERRAIN_FAILSAFE); copter.set_mode(LAND, MODE_REASON_TERRAIN_FAILSAFE);
return; return;
} }
@ -432,7 +432,7 @@ void Copter::ModeRTL::compute_return_target(bool terrain_following_allowed)
!rtl_path.return_target.get_alt_cm(Location::AltFrame::ABOVE_TERRAIN, return_target_terr_alt) || !rtl_path.return_target.get_alt_cm(Location::AltFrame::ABOVE_TERRAIN, return_target_terr_alt) ||
!copter.current_loc.get_alt_cm(Location::AltFrame::ABOVE_TERRAIN, curr_alt)) { !copter.current_loc.get_alt_cm(Location::AltFrame::ABOVE_TERRAIN, curr_alt)) {
rtl_path.terrain_used = false; rtl_path.terrain_used = false;
copter.Log_Write_Error(ERROR_SUBSYSTEM_TERRAIN, ERROR_CODE_MISSING_TERRAIN_DATA); AP::logger().Write_Error(LogErrorSubsystem::TERRAIN, LogErrorCode::MISSING_TERRAIN_DATA);
} }
} }

View File

@ -136,7 +136,7 @@ void Copter::read_radio()
} }
// Nobody ever talks to us. Log an error and enter failsafe. // Nobody ever talks to us. Log an error and enter failsafe.
Log_Write_Error(ERROR_SUBSYSTEM_RADIO, ERROR_CODE_RADIO_LATE_FRAME); AP::logger().Write_Error(LogErrorSubsystem::RADIO, LogErrorCode::RADIO_LATE_FRAME);
set_failsafe_radio(true); set_failsafe_radio(true);
} }

View File

@ -96,7 +96,7 @@ void Copter::init_compass()
if (!compass.read()) { if (!compass.read()) {
// make sure we don't pass a broken compass to DCM // make sure we don't pass a broken compass to DCM
hal.console->printf("COMPASS INIT ERROR\n"); hal.console->printf("COMPASS INIT ERROR\n");
Log_Write_Error(ERROR_SUBSYSTEM_COMPASS,ERROR_CODE_FAILED_TO_INITIALISE); AP::logger().Write_Error(LogErrorSubsystem::COMPASS, LogErrorCode::FAILED_TO_INITIALISE);
return; return;
} }
ahrs.set_compass(&compass); ahrs.set_compass(&compass);