mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Motors: Heli: remove loop rate "RSC control mode change failed" meassage
This commit is contained in:
parent
c5f3d5a98b
commit
3e246c9d25
@ -242,7 +242,6 @@ void AP_MotorsHeli_Dual::calculate_armed_scalars()
|
||||
if (_main_rotor._rsc_mode.get() != _main_rotor.get_control_mode()) {
|
||||
_main_rotor.reset_rsc_mode_param();
|
||||
_heliflags.save_rsc_mode = true;
|
||||
gcs().send_text(MAV_SEVERITY_CRITICAL, "RSC control mode change failed");
|
||||
}
|
||||
// saves rsc mode parameter when disarmed if it had been reset while armed
|
||||
if (_heliflags.save_rsc_mode && !armed()) {
|
||||
|
@ -73,7 +73,6 @@ void AP_MotorsHeli_Quad::calculate_armed_scalars()
|
||||
// keeps user from changing RSC mode while armed
|
||||
if (_main_rotor._rsc_mode.get() != _main_rotor.get_control_mode()) {
|
||||
_main_rotor.reset_rsc_mode_param();
|
||||
gcs().send_text(MAV_SEVERITY_CRITICAL, "RSC control mode change failed");
|
||||
_heliflags.save_rsc_mode = true;
|
||||
}
|
||||
// saves rsc mode parameter when disarmed if it had been reset while armed
|
||||
|
@ -243,7 +243,6 @@ void AP_MotorsHeli_Single::calculate_armed_scalars()
|
||||
// keeps user from changing RSC mode while armed
|
||||
if (_main_rotor._rsc_mode.get() != _main_rotor.get_control_mode()) {
|
||||
_main_rotor.reset_rsc_mode_param();
|
||||
gcs().send_text(MAV_SEVERITY_CRITICAL, "RSC control mode change failed");
|
||||
_heliflags.save_rsc_mode = true;
|
||||
}
|
||||
// saves rsc mode parameter when disarmed if it had been reset while armed
|
||||
|
Loading…
Reference in New Issue
Block a user