mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Generator: mask MaintenanceRequired out from error bits in prearm
Turns out the generator sets this bit when it reaches the maintenance-required state. Mask it out from the error bits so the user can still fly. Add some periodically-run code to complain about maintenance-required, separate from the prearm checks.
This commit is contained in:
parent
c496985e37
commit
bc0befc737
@ -194,6 +194,23 @@ constexpr float AP_Generator_RichenPower::heat_required_for_run()
|
||||
}
|
||||
|
||||
|
||||
void AP_Generator_RichenPower::check_maintenance_required()
|
||||
{
|
||||
// don't bother the user while flying:
|
||||
if (hal.util->get_soft_armed()) {
|
||||
return;
|
||||
}
|
||||
|
||||
const uint32_t now = AP_HAL::millis();
|
||||
|
||||
if (last_reading.errors & (1U<<uint16_t(Errors::MaintenanceRequired))) {
|
||||
if (now - last_maintenance_warning_ms > 60000) {
|
||||
gcs().send_text(MAV_SEVERITY_NOTICE, "Generator: requires maintenance");
|
||||
last_maintenance_warning_ms = now;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
update the state of the sensor
|
||||
*/
|
||||
@ -205,6 +222,7 @@ void AP_Generator_RichenPower::update(void)
|
||||
|
||||
if (last_reading_ms != 0) {
|
||||
update_runstate();
|
||||
check_maintenance_required();
|
||||
}
|
||||
|
||||
(void)get_reading();
|
||||
@ -335,17 +353,22 @@ bool AP_Generator_RichenPower::pre_arm_check(char *failmsg, uint8_t failmsg_len)
|
||||
hal.util->snprintf(failmsg, failmsg_len, "no messages in %ums", unsigned(now - last_reading_ms));
|
||||
return false;
|
||||
}
|
||||
if (last_reading.seconds_until_maintenance == 0) {
|
||||
hal.util->snprintf(failmsg, failmsg_len, "requires maintenance");
|
||||
}
|
||||
if (SRV_Channels::get_channel_for(SRV_Channel::k_generator_control) == nullptr) {
|
||||
hal.util->snprintf(failmsg, failmsg_len, "need a servo output channel");
|
||||
return false;
|
||||
}
|
||||
|
||||
if (last_reading.errors) {
|
||||
uint16_t errors = last_reading.errors;
|
||||
|
||||
// requiring maintenance isn't something that should stop
|
||||
// people flying - they have work to do. But we definitely
|
||||
// complain about it - a lot.
|
||||
errors &= ~(1U << uint16_t(Errors::MaintenanceRequired));
|
||||
|
||||
if (errors) {
|
||||
|
||||
for (uint16_t i=0; i<16; i++) {
|
||||
if (last_reading.errors & (1U << (uint16_t)i)) {
|
||||
if (errors & (1U << i)) {
|
||||
if (i < (uint16_t)Errors::LAST) {
|
||||
hal.util->snprintf(failmsg, failmsg_len, "error: %s", error_strings[i]);
|
||||
} else {
|
||||
|
@ -204,5 +204,11 @@ private:
|
||||
}
|
||||
return AP_HAL::millis() - idle_state_start_ms;
|
||||
}
|
||||
|
||||
// check if the generator requires maintenance and send a message if it does:
|
||||
void check_maintenance_required();
|
||||
// if we are emitting warnings about the generator requiring
|
||||
// maintenamce, this is the last time we sent the warning:
|
||||
uint32_t last_maintenance_warning_ms;
|
||||
};
|
||||
#endif
|
||||
|
Loading…
Reference in New Issue
Block a user