mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 12:38:33 -04:00
AP_Vehicle: log internal error and report bitmask to GCS
AP_Vehicle.cpp: cast parameter bitmask as (unsigned) per Peter B. rework per Peter B. Co-authored-by: Peter Barker <pb-gh@barker.dropbear.id.au> remove unnecessary send_internal_error_statustext function remove Write_InternalError function
This commit is contained in:
parent
2be49cb42b
commit
0a236bc13d
@ -200,6 +200,7 @@ enum class LogErrorSubsystem : uint8_t {
|
||||
FAILSAFE_LEAK = 27,
|
||||
PILOT_INPUT = 28,
|
||||
FAILSAFE_VIBE = 29,
|
||||
INTERNAL_ERROR = 30,
|
||||
};
|
||||
|
||||
// bizarrely this enumeration has lots of duplicate values, offering
|
||||
@ -229,6 +230,8 @@ enum class LogErrorCode : uint8_t {
|
||||
FAILED_CIRCLE_INIT = 4,
|
||||
DEST_OUTSIDE_FENCE = 5,
|
||||
RTL_MISSING_RNGFND = 6,
|
||||
// subsystem specific error codes -- internal_error
|
||||
INTERNAL_ERRORS_DETECTED = 1,
|
||||
|
||||
// parachute failed to deploy because of low altitude or landed
|
||||
PARACHUTE_TOO_LOW = 2,
|
||||
|
@ -199,6 +199,12 @@ void AP_Vehicle::loop()
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s", banner_msg);
|
||||
}
|
||||
}
|
||||
const uint32_t new_internal_errors = AP::internalerror().errors();
|
||||
if(_last_internal_errors != new_internal_errors) {
|
||||
AP::logger().Write_Error(LogErrorSubsystem::INTERNAL_ERROR, LogErrorCode::INTERNAL_ERRORS_DETECTED);
|
||||
gcs().send_text(MAV_SEVERITY_CRITICAL, "Internal Errors %x", (unsigned)new_internal_errors);
|
||||
_last_internal_errors = new_internal_errors;
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -373,6 +373,8 @@ private:
|
||||
static AP_Vehicle *_singleton;
|
||||
|
||||
bool done_safety_init;
|
||||
|
||||
uint32_t _last_internal_errors; // backup of AP_InternalError::internal_errors bitmask
|
||||
};
|
||||
|
||||
namespace AP {
|
||||
|
Loading…
Reference in New Issue
Block a user