mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Arming: Add a RC check that (<= min trim max) for all channels
This commit is contained in:
parent
d2429fa0bc
commit
1b18a78d1d
@ -455,7 +455,28 @@ bool AP_Arming::hardware_safety_check(bool report)
|
||||
|
||||
bool AP_Arming::rc_calibration_checks(bool report)
|
||||
{
|
||||
return true;
|
||||
bool check_passed = true;
|
||||
for (uint8_t i = 0; i < NUM_RC_CHANNELS; i++) {
|
||||
const RC_Channel *ch = RC_Channels::rc_channel(i);
|
||||
if (ch == nullptr) {
|
||||
continue;
|
||||
}
|
||||
const uint16_t trim = ch->get_radio_trim();
|
||||
if (ch->get_radio_min() > trim) {
|
||||
if (report) {
|
||||
gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: RC%d minimum is greater than trim", i + 1);
|
||||
}
|
||||
check_passed = false;
|
||||
}
|
||||
if (ch->get_radio_max() < trim) {
|
||||
if (report) {
|
||||
gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: RC%d maximum is less than trim", i + 1);
|
||||
}
|
||||
check_passed = false;
|
||||
}
|
||||
}
|
||||
|
||||
return check_passed;
|
||||
}
|
||||
|
||||
bool AP_Arming::manual_transmitter_checks(bool report)
|
||||
|
Loading…
Reference in New Issue
Block a user